From 6f3f503da15aa838af91396ae8d138d4e54404c0 Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Tue, 16 Feb 2016 14:51:12 -0800 Subject: [PATCH 001/124] Updated README file. --- camera/README.md | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/camera/README.md b/camera/README.md index 3f82ce9f53..428ddf0afb 100644 --- a/camera/README.md +++ b/camera/README.md @@ -134,12 +134,11 @@ Type the following to launch the camera nodelet. You will notice the camera ligh View using RVIZ: For color, infrared1 and infrared2 streams, you can open RVIZ and load the published topics. -For the point cloud steam, before loading its corresponding topic, set the camera_depth_optical_frame using following command: +For the point cloud stream, before loading its corresponding topic, set the camera_depth_optical_frame using following command: $ rosrun tf static_transform_publisher 0.0 0.0 0.0 0.0 0.0 0.0 map camera_depth_optical_frame 100 You can also open RVIZ and load the provided RVIZ configuration file: realsenseRvizConfiguration.rviz. -![](docs/realsenseRvizScreenshot.png) View using other commands: * For color stream @@ -173,7 +172,7 @@ View using other commands: ** The ROS integration has been tested on a 64bit machine with Linux 14.04 (Trusty) and ROS Indigo. ###Limitations: -Currently camera ROS node supports following formats +Currently, the ROS camera nodelet only supports the following formats: * Color stream: RGB8 * Depth stream: Y16 * Infrared stream: Y8 From a8cb207ace01bbfcaf4856d1fa489a8502a771db Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Tue, 16 Feb 2016 15:53:53 -0800 Subject: [PATCH 002/124] Update the README to reflect the external librealsense git repo. Included the unit test commands in the main README and removed the README within the test folder. --- camera/README.md | 51 +++++++++++----- camera/test/README.md | 132 ------------------------------------------ 2 files changed, 38 insertions(+), 145 deletions(-) delete mode 100644 camera/test/README.md diff --git a/camera/README.md b/camera/README.md index 428ddf0afb..fd9660906b 100644 --- a/camera/README.md +++ b/camera/README.md @@ -4,21 +4,20 @@ ###Installation #####Getting the camera to work on Linux -* Clone the source from the librealsense git repository https://github.intel.com/PerCSystemsEngineering/librealsense. -* Follow the instructions at https://github.intel.com/PerCSystemsEngineering/librealsense/blob/master/doc/installation.md. +* Clone the source from the librealsense git repository https://github.com/IntelRealSense/librealsense.git and follow the "Installation Guide" for installing the library. * Make sure that the software stack is installed properly and that the camera is working. This can be checked by connecting the camera to a USB3 port and running the "cpp-capture" sample program in the "librealsense/bin" folder. If this does not work, you should first fix this issue before continuing with the ROS integration. -* Make sure /usr/local/lib is in your LD__LIBRARY_PATH. +* Make sure "/usr/local/lib" is set in your "LD_LIBRARY_PATH". #####Building package: * Follow the steps in the README.md file of the ros repository. Setup ROS and create a local catkin workspace. * To compile just realsense package, instead of catkin_make, execute following command - catkin_make --pkg realsense + catkin_make --pkg realsense_camera -Successful execution of command will build target “r200_camera_nodelet” +Successful execution of command will build target “realsense_camera_nodelet” -Sample launch files are available in realsense/launch directory +Sample launch files are available in camera/launch directory realsense_r200_launch_preset.launch @@ -123,13 +122,12 @@ Infrared2 camera ####Services get_settings (camera/get_settings) To get supported camera options with current value set. It returns string in options:value format where different options are seperated by semicolon. - ###Running the R200 nodelet -Type the following to launch the camera nodelet. You will notice the camera light up. +Use the following command to launch the camera nodelet. You will notice the camera light up. - $ roslaunch realsense realsense_r200_launch_preset.launch + $ roslaunch realsense_camera realsense_r200_launch_preset.launch View using RVIZ: @@ -141,23 +139,23 @@ For the point cloud stream, before loading its corresponding topic, set the came You can also open RVIZ and load the provided RVIZ configuration file: realsenseRvizConfiguration.rviz. View using other commands: -* For color stream +For color stream $ rosrun image_view image_view image:=/camera/color/image_raw -* For depth stream +For depth stream $ rostopic echo /camera/depth/image_raw $ rostopic echo /camera/depth/camera_info -* For pointcloud +For pointcloud $ rosrun pcl_ros convert_pointcloud_to_image input:=/camera/depth/points output:=/my_image $ rosrun image_view image_view image:=/my_image -* For viewing supported camera settings with current values: +For viewing supported camera settings with current values: $ rosservice call /camera/get_settings @@ -171,6 +169,33 @@ View using other commands: ** The ROS integration has been tested on a 64bit machine with Linux 14.04 (Trusty) and ROS Indigo. +###Unit Tests +The Unit Tests can be executed using either of the methods: + +1. Using rostest command with test files + + $ rostest + E.g. rostest realsense_r200_depth_only.test + +2. Using rosrun command + + $ roslaunch realsense_camera realsense_r200_launch_manual.launch + + $ rosrun realsense_camera realsense_camera_test + E.g. rosrun realsense_camera realsense_camera_test enable_depth 1 depth_encoding 16UC1 depth_height 360 depth_width 480 depth_step 960 enable_color 1 color_encoding rgb8 color_height 480 color_width 640 color_step 1920 + +Sample testfiles are available in test directory + +realsense_r200_color_only.test + +realsense_r200_depth_only.test + +realsense_r200_resolution.test + +realsense_r200_settings.test + +Both of these methods first starts "RealsenseNodelet" for Intel® RealSense™ R200 (DS4) camera and then executes all the unit tests. + ###Limitations: Currently, the ROS camera nodelet only supports the following formats: * Color stream: RGB8 diff --git a/camera/test/README.md b/camera/test/README.md deleted file mode 100644 index d38cd299ea..0000000000 --- a/camera/test/README.md +++ /dev/null @@ -1,132 +0,0 @@ -#Intel® ROS RealSense Package - Unit Testing -###(ROS Indigo + Ubuntu 14.04 [64-bit]) -ROS node unit test (rostest + gtest): node unit tests start up "RealsenseNodelet" and test its published topics, supported parameter values and services. - -#####Building package: - -* Follow the steps in the README.md file of the ros repository. Setup ROS and create a local catkin workspace. -* To compile just realsense package, instead of catkin_make, execute following command - catkin_make --pkg realsense - -Successful execution of command will build target "utest" along with target “r200_camera_nodelet” - -#### Subscribed Topics -Color camera - - camera/color/image_raw (sensor_msgs/Image) - Color rectified image. RGB format. - camera/color/camera_info - Calibration data - -Depth camera - - camera/depth/image_raw (sensor_msgs/Image) - uint16 depths in mm - camera/depth/camera_info - Calibration data - camera/depth/points (sensor_msgs/PointCloud2) - Registered XYZRGB point cloud. - -Infrared1 camera - - camera/infrared1/image_raw (sensor_msgs/Image) - camera/infrared1/camera_info - Calibration data - -Infrared2 camera - - camera/infrared2/image_raw (sensor_msgs/Image) - camera/infrared2/camera_info - Calibration data - -####Parameters - - mode (string, default: preset) - Specify the mode to start camera streams. Mode comprises of height, width and fps. - Preset mode enables default values whereas Manual mode enables the specified parameter values. - color_height (int, default: 480) - Specify the color camera height resolution. - color_width (int, default: 640) - Specify the color camera width resolution. - depth_height (int, default: 360) - Specify the depth camera height resolution. - depth_width (int, default: 480) - Specify the depth camera width resolution. - depth_fps (int, default: 60) - Specify the color camera FPS - depth_fps (int, default: 60) - Specify the depth camera FPS - enable_depth (bool, default: 1) - Specify if to enable or not the depth camera. 1 is true. 0 is false. - enable_color (bool, default: 1) - Specify if to enable or not the color camera. 1 is true. 0 is false. - enable_pointcloud (bool, default: 1) - Specify if to enable or not the point cloud camera. 1 is true. 0 is false. - camera (string, default: "R200") - Specify the camera name. - Supported options: Here are r200 camera supported options that can be set - COLOR_BACKLIGHT_COMPENSATION : [0, 4] - COLOR_BRIGHTNESS : [0, 255] - COLOR_CONTRAST : [16, 64] - COLOR_EXPOSURE : [0, 0] - COLOR_GAIN : [0, 256] - COLOR_GAMMA : [100, 280] - COLOR_HUE : [-2200, 2200] - COLOR_SATURATION : [0, 255] - COLOR_SHARPNESS : [0, 7] - COLOR_WHITE_BALANCE : [2000, 8000] - COLOR_ENABLE_AUTO_EXPOSURE : [0, 0] - COLOR_ENABLE_AUTO_WHITE_BALANCE : [0, 1] - R200_LR_AUTO_EXPOSURE_ENABLED : [0, 1] - R200_LR_GAIN : [100, 1600] - R200_LR_EXPOSURE : [0, 333] - R200_EMITTER_ENABLED : [0, 1] - R200_DEPTH_CONTROL_PRESET : [0, 5] - R200_DEPTH_UNITS : [1, 2147483647] - R200_DEPTH_CLAMP_MIN : [0, 65535] - R200_DEPTH_CLAMP_MAX : [0, 65535] - R200_DISPARITY_MULTIPLIER : [1, 1000] - R200_DEPTH_CONTROL_ESTIMATE_MEDIAN_DECREMENT : [0 - 255] - R200_DEPTH_CONTROL_ESTIMATE_MEDIAN_INCREMENT : [0 - 255] - R200_DEPTH_CONTROL_MEDIAN_THRESHOLD : [0 - 1023] - R200_DEPTH_CONTROL_SCORE_MINIMUM_THRESHOLD : [0 - 1023] - R200_DEPTH_CONTROL_SCORE_MAXIMUM_THRESHOLD : [0 - 1023] - R200_DEPTH_CONTROL_TEXTURE_COUNT_THRESHOLD : [0 - 31] - R200_DEPTH_CONTROL_TEXTURE_DIFFERENCE_THRESHOLD : [0 - 1023] - R200_DEPTH_CONTROL_SECOND_PEAK_THRESHOLD : [0 - 1023] - R200_DEPTH_CONTROL_NEIGHBOR_THRESHOLD : [0 - 1023] - R200_DEPTH_CONTROL_LR_THRESHOLD : [0 - 2047] - -####Services called - get_settings (camera/get_settings) - To get supported camera options with current value set. - - -###Running the utest node -The Unit Tests can be executed using either of the methods: - -1. Using rostest command with test files - - $ rostest - e.g rostest realsense_tests_r200_depth_only.test - -2. Using rosrun command - - $ roslaunch realsense realsense_r200_launch_manual.launch - - $ rosrun realsense_tests utest - e.g rosrun realsense_tests utest enable_depth 1 depth_encoding 16UC1 depth_height 360 depth_width 480 depth_step 960 enable_color 1 color_encoding rgb8 color_height 480 color_width 640 color_step 1920 - -Sample testfiles are available in test directory - -realsense_tests_r200_color_only.test - -realsense_tests_r200_depth_only.test - -realsense_tests_r200_resolution.test - -realsense_tests_r200_settings.test - -Both of these methods first starts "RealsenseNodelet" for Intel® RealSense™ R200 (DS4) camera and then executes all the unittests. - - From 6bcf2f5d184337e5e8f5cee8683ca846bb0208d3 Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Tue, 16 Feb 2016 15:55:49 -0800 Subject: [PATCH 003/124] Updated README. --- camera/README.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/camera/README.md b/camera/README.md index fd9660906b..2cf330e9fc 100644 --- a/camera/README.md +++ b/camera/README.md @@ -172,12 +172,12 @@ For viewing supported camera settings with current values: ###Unit Tests The Unit Tests can be executed using either of the methods: -1. Using rostest command with test files +Using rostest command with test files $ rostest E.g. rostest realsense_r200_depth_only.test -2. Using rosrun command +Using rosrun command $ roslaunch realsense_camera realsense_r200_launch_manual.launch From 061d8a70568a4b7cdd0b16097badc22821ab2f24 Mon Sep 17 00:00:00 2001 From: Mark D Horn Date: Tue, 16 Feb 2016 17:42:30 -0800 Subject: [PATCH 004/124] Remove Unused ROS Python Dependency --- camera/CMakeLists.txt | 1 - camera/package.xml | 2 -- 2 files changed, 3 deletions(-) diff --git a/camera/CMakeLists.txt b/camera/CMakeLists.txt index 42e6acc0e2..a1533e9bc7 100644 --- a/camera/CMakeLists.txt +++ b/camera/CMakeLists.txt @@ -6,7 +6,6 @@ set(CMAKE_CXX_FLAGS "-std=c++11 ${CMAKE_CXX_FLAGS}") find_package(catkin REQUIRED COMPONENTS roscpp - rospy nodelet cv_bridge image_transport diff --git a/camera/package.xml b/camera/package.xml index eb80033386..1033ead43f 100644 --- a/camera/package.xml +++ b/camera/package.xml @@ -16,7 +16,6 @@ catkin roscpp - rospy nodelet cv_bridge image_transport @@ -29,7 +28,6 @@ pcl_ros roscpp - rospy nodelet cv_bridge image_transport From 4acfbc1d4461b1f514134411acf1f389101ccda4 Mon Sep 17 00:00:00 2001 From: Mark D Horn Date: Tue, 16 Feb 2016 17:43:13 -0800 Subject: [PATCH 005/124] Remove Old README.md This file was intend to have build directions and is now outdated. If the README exists at this level it should describe the Stack. --- README.md | 21 --------------------- 1 file changed, 21 deletions(-) delete mode 100644 README.md diff --git a/README.md b/README.md deleted file mode 100644 index 63bc061a88..0000000000 --- a/README.md +++ /dev/null @@ -1,21 +0,0 @@ -# ros -ROS Development - - -## Usage -* Setup for ROS - - `source /opt/ros/`*``*`/setup.bash` - -* Create your Catkin Workspace - - `mkdir catkin_ws` -* Clone the repository as the `src` directory - - `git clone https://github.com/otcshare/ros-realsense.git src` -* Build the Nodes - - `catkin_make` -* Setup to use newly build Nodes - - `source devel/setup.bash` From 3fa2f281e885c47f6f424da27d6de3ff4915870b Mon Sep 17 00:00:00 2001 From: Mark D Horn Date: Tue, 16 Feb 2016 17:45:18 -0800 Subject: [PATCH 006/124] Add dependency for the generated service files --- camera/CMakeLists.txt | 2 ++ 1 file changed, 2 insertions(+) diff --git a/camera/CMakeLists.txt b/camera/CMakeLists.txt index a1533e9bc7..99ae8cf90f 100644 --- a/camera/CMakeLists.txt +++ b/camera/CMakeLists.txt @@ -37,9 +37,11 @@ target_link_libraries(realsense_camera_nodelet ${catkin_LIBRARIES} /usr/local/lib/librealsense.so ) +add_dependencies(realsense_camera_nodelet realsense_camera_generate_messages_cpp) add_executable(realsense_camera_test test/realsense_camera_test_node.cpp) target_link_libraries(realsense_camera_test ${catkin_LIBRARIES} ${GTEST_LIBRARIES} ) +add_dependencies(realsense_camera_test realsense_camera_generate_messages_cpp) From 59e6fcb6c561a438805fad6dacc571f3df021e7c Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Wed, 17 Feb 2016 13:08:14 -0800 Subject: [PATCH 007/124] Updated README to specify copying of librealsense include files. --- camera/README.md | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/camera/README.md b/camera/README.md index 2cf330e9fc..107113403e 100644 --- a/camera/README.md +++ b/camera/README.md @@ -8,12 +8,12 @@ * Make sure that the software stack is installed properly and that the camera is working. This can be checked by connecting the camera to a USB3 port and running the "cpp-capture" sample program in the "librealsense/bin" folder. If this does not work, you should first fix this issue before continuing with the ROS integration. * Make sure "/usr/local/lib" is set in your "LD_LIBRARY_PATH". +* Copy the librealsense header files folder "librealsense/include/librealsense" to "/usr/local/include". #####Building package: -* Follow the steps in the README.md file of the ros repository. Setup ROS and create a local catkin workspace. -* To compile just realsense package, instead of catkin_make, execute following command - catkin_make --pkg realsense_camera +* Setup ROS and create a local catkin workspace. +* Compile the realsense_camera package by executing the catkin_make command. Successful execution of command will build target “realsense_camera_nodelet” From e00fbf7f3b9f3ae16ff6685107927591be318af4 Mon Sep 17 00:00:00 2001 From: Matt Hansen Date: Wed, 17 Feb 2016 16:28:45 -0800 Subject: [PATCH 008/124] Update README.md Added commands for easy viewing in RVIZ --- camera/README.md | 7 ++++++- 1 file changed, 6 insertions(+), 1 deletion(-) diff --git a/camera/README.md b/camera/README.md index 107113403e..d2482b07a3 100644 --- a/camera/README.md +++ b/camera/README.md @@ -132,11 +132,16 @@ Use the following command to launch the camera nodelet. You will notice the came View using RVIZ: For color, infrared1 and infrared2 streams, you can open RVIZ and load the published topics. + +You can also open RVIZ and load the provided RVIZ configuration file: realsenseRvizConfiguration.rviz. +``` + $ roscd realsense_camera + $ rosrun rviz rviz -d rviz/realsenseRvizConfiguration.rviz +``` For the point cloud stream, before loading its corresponding topic, set the camera_depth_optical_frame using following command: $ rosrun tf static_transform_publisher 0.0 0.0 0.0 0.0 0.0 0.0 map camera_depth_optical_frame 100 -You can also open RVIZ and load the provided RVIZ configuration file: realsenseRvizConfiguration.rviz. View using other commands: For color stream From e161975f819413068b3959feed130ac8659f36b1 Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Wed, 17 Feb 2016 22:55:07 -0800 Subject: [PATCH 009/124] Modified .cpp file to read depth and camera frame ids from args. Added two new launch files to enable rgbd launch. Renamed existing launch files to distinguish standalone nodelets from others. --- camera/.cproject | 41 +-- camera/README.md | 12 +- camera/launch/realsense_r200_nodelet.launch | 21 ++ ...nse_r200_nodelet_standalone_manual.launch} | 0 ...nse_r200_nodelet_standalone_preset.launch} | 6 +- ...e_r200_nodelet_standalone_settings.launch} | 0 camera/launch/realsense_r200_rgbd.launch | 93 +++++++ ....rviz => realsenseRvizConfiguration1.rviz} | 0 camera/rviz/realsenseRvizConfiguration2.rviz | 245 ++++++++++++++++++ camera/src/realsense_camera_nodelet.cpp | 10 + camera/test/realsense_r200_color_only.test | 8 +- camera/test/realsense_r200_depth_only.test | 6 +- camera/test/realsense_r200_resolution.test | 13 +- 13 files changed, 412 insertions(+), 43 deletions(-) create mode 100644 camera/launch/realsense_r200_nodelet.launch rename camera/launch/{realsense_r200_launch_manual.launch => realsense_r200_nodelet_standalone_manual.launch} (100%) rename camera/launch/{realsense_r200_launch_preset.launch => realsense_r200_nodelet_standalone_preset.launch} (81%) rename camera/launch/{realsense_r200_launch_settings.launch => realsense_r200_nodelet_standalone_settings.launch} (100%) create mode 100644 camera/launch/realsense_r200_rgbd.launch rename camera/rviz/{realsenseRvizConfiguration.rviz => realsenseRvizConfiguration1.rviz} (100%) create mode 100644 camera/rviz/realsenseRvizConfiguration2.rviz diff --git a/camera/.cproject b/camera/.cproject index 7775a24d88..ca7ca6b28a 100644 --- a/camera/.cproject +++ b/camera/.cproject @@ -1,8 +1,8 @@ - - + + @@ -14,20 +14,20 @@ - - - - - - - - + + + + + + + + - - + + - - + + @@ -37,27 +37,30 @@ - + + + + - - + + - - + + diff --git a/camera/README.md b/camera/README.md index d2482b07a3..dc48fcfd7f 100644 --- a/camera/README.md +++ b/camera/README.md @@ -19,11 +19,11 @@ Successful execution of command will build target “realsense_camera_nodelet Sample launch files are available in camera/launch directory -realsense_r200_launch_preset.launch +realsense_r200_nodelet_standalone_preset.launch -realsense_r200_launch_manual.launch +realsense_r200_nodelet_standalone_manual.launch -realsense_r200_launch_settings.launch +realsense_r200_rgbd.launch ### Intel® RealSense™ R200 Nodelet Publishing stream data from the Intel® RealSense™ R200 (DS4) camera @@ -31,7 +31,7 @@ Publishing stream data from the Intel® RealSense™ R200 (DS4) camera #### Subscribed Topics None -#### Published Topics +#### Published Topics (default) Color camera @@ -133,10 +133,10 @@ View using RVIZ: For color, infrared1 and infrared2 streams, you can open RVIZ and load the published topics. -You can also open RVIZ and load the provided RVIZ configuration file: realsenseRvizConfiguration.rviz. +You can also open RVIZ and load the provided RVIZ configuration file: realsenseRvizConfiguration1.rviz. ``` $ roscd realsense_camera - $ rosrun rviz rviz -d rviz/realsenseRvizConfiguration.rviz + $ rosrun rviz rviz -d rviz/realsenseRvizConfiguration1.rviz ``` For the point cloud stream, before loading its corresponding topic, set the camera_depth_optical_frame using following command: diff --git a/camera/launch/realsense_r200_nodelet.launch b/camera/launch/realsense_r200_nodelet.launch new file mode 100644 index 0000000000..9bc1944bb0 --- /dev/null +++ b/camera/launch/realsense_r200_nodelet.launch @@ -0,0 +1,21 @@ + + + + + + + + + + + + + + + + + + diff --git a/camera/launch/realsense_r200_launch_manual.launch b/camera/launch/realsense_r200_nodelet_standalone_manual.launch similarity index 100% rename from camera/launch/realsense_r200_launch_manual.launch rename to camera/launch/realsense_r200_nodelet_standalone_manual.launch diff --git a/camera/launch/realsense_r200_launch_preset.launch b/camera/launch/realsense_r200_nodelet_standalone_preset.launch similarity index 81% rename from camera/launch/realsense_r200_launch_preset.launch rename to camera/launch/realsense_r200_nodelet_standalone_preset.launch index a1a00ed2ce..42029217ca 100644 --- a/camera/launch/realsense_r200_launch_preset.launch +++ b/camera/launch/realsense_r200_nodelet_standalone_preset.launch @@ -3,7 +3,7 @@ - + @@ -12,7 +12,7 @@ mode $(arg mode) enable_color $(arg enable_color) enable_depth $(arg enable_depth) - enable_pointcloud $(arg enable_pointcloud)"> + enable_pointcloud $(arg enable_pointcloud)"> - + diff --git a/camera/launch/realsense_r200_launch_settings.launch b/camera/launch/realsense_r200_nodelet_standalone_settings.launch similarity index 100% rename from camera/launch/realsense_r200_launch_settings.launch rename to camera/launch/realsense_r200_nodelet_standalone_settings.launch diff --git a/camera/launch/realsense_r200_rgbd.launch b/camera/launch/realsense_r200_rgbd.launch new file mode 100644 index 0000000000..137ca0c354 --- /dev/null +++ b/camera/launch/realsense_r200_rgbd.launch @@ -0,0 +1,93 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/camera/rviz/realsenseRvizConfiguration.rviz b/camera/rviz/realsenseRvizConfiguration1.rviz similarity index 100% rename from camera/rviz/realsenseRvizConfiguration.rviz rename to camera/rviz/realsenseRvizConfiguration1.rviz diff --git a/camera/rviz/realsenseRvizConfiguration2.rviz b/camera/rviz/realsenseRvizConfiguration2.rviz new file mode 100644 index 0000000000..370c7d924e --- /dev/null +++ b/camera/rviz/realsenseRvizConfiguration2.rviz @@ -0,0 +1,245 @@ +Panels: + - Class: rviz/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Status1 + - /Image1 + - /Image2 + - /Image3 + - /Image4 + - /Image5 + - /PointCloud21 + Splitter Ratio: 0.5 + Tree Height: 775 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.588679 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: Image +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.03 + 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 + - Class: rviz/Image + Enabled: false + Image Topic: /camera/depth/image_raw + Max Value: 6000 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: false + Queue Size: 2 + Transport Hint: raw + Value: false + - Class: rviz/Image + Enabled: false + Image Topic: /camera/depth/image + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: false + Queue Size: 2 + Transport Hint: raw + Value: false + - Class: rviz/Image + Enabled: true + Image Topic: /camera/depth/image_raw + Max Value: 3500 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: false + Queue Size: 2 + Transport Hint: raw + Value: true + - Class: rviz/Image + Enabled: true + Image Topic: /camera/depth/image_rect + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: false + Queue Size: 2 + Transport Hint: raw + Value: true + - Class: rviz/Image + Enabled: true + Image Topic: /camera/depth/image_rect_raw + Max Value: 3500 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: false + Queue Size: 2 + Transport Hint: raw + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: Intensity + 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: PointCloud2 + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.01 + Style: Flat Squares + Topic: /camera/depth/points + Use Fixed Frame: true + Use rainbow: true + Value: true + - Class: rviz/Image + Enabled: true + Image Topic: /camera/ir/image_rect_ir + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: true + Queue Size: 2 + Transport Hint: raw + Value: true + - Class: rviz/Image + Enabled: true + Image Topic: /camera/ir/image_raw + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: true + Queue Size: 2 + Transport Hint: raw + Value: true + - Class: rviz/Image + Enabled: true + Image Topic: /camera/rgb/image_rect_color + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: true + Queue Size: 2 + Transport Hint: raw + Value: true + - Class: rviz/Image + Enabled: true + Image Topic: /camera/rgb/image_rect_mono + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: true + Queue Size: 2 + Transport Hint: raw + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + 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 + Topic: /initialpose + - 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: 10 + Enable Stereo Rendering: + Stereo Eye Separation: 0.06 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: 0 + Y: 0 + Z: 0 + Name: Current View + Near Clip Distance: 0.01 + Pitch: 0.785398 + Target Frame: + Value: Orbit (rviz) + Yaw: 0.785398 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 1056 + Hide Left Dock: false + Hide Right Dock: false + Image: + collapsed: false + QMainWindow State: 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 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1855 + X: 55 + Y: -14 diff --git a/camera/src/realsense_camera_nodelet.cpp b/camera/src/realsense_camera_nodelet.cpp index d98267cabf..99a81d64a1 100644 --- a/camera/src/realsense_camera_nodelet.cpp +++ b/camera/src/realsense_camera_nodelet.cpp @@ -382,6 +382,16 @@ namespace realsense_camera camera_ = config_.at ("camera").c_str (); } + if (config_.find ("depth_frame_id") != config_.end ()) + { + frame_id_[RS_STREAM_DEPTH] = config_.at ("depth_frame_id").c_str (); + } + + if (config_.find ("color_frame_id") != config_.end ()) + { + frame_id_[RS_STREAM_COLOR] = config_.at ("color_frame_id").c_str (); + } + if (mode_.compare ("manual") == 0) { if (config_.find ("color_fps") != config_.end ()) diff --git a/camera/test/realsense_r200_color_only.test b/camera/test/realsense_r200_color_only.test index 76f5a34472..1d6cbc71fb 100644 --- a/camera/test/realsense_r200_color_only.test +++ b/camera/test/realsense_r200_color_only.test @@ -1,10 +1,10 @@ - - + - + args="enable_depth 0 enable_color 1" /> + diff --git a/camera/test/realsense_r200_depth_only.test b/camera/test/realsense_r200_depth_only.test index d3046af01d..79f0afe71c 100644 --- a/camera/test/realsense_r200_depth_only.test +++ b/camera/test/realsense_r200_depth_only.test @@ -1,12 +1,10 @@ - - + - + args="enable_depth 1 enable_color 0" /> diff --git a/camera/test/realsense_r200_resolution.test b/camera/test/realsense_r200_resolution.test index 57584445f8..65d893ed8d 100644 --- a/camera/test/realsense_r200_resolution.test +++ b/camera/test/realsense_r200_resolution.test @@ -1,15 +1,14 @@ - - + - + - + - - + args="color_height 1080 color_width 1920 depth_height 468 depth_width 628 color_fps 30 depth_fps 30" /> + From 1fdee60dfab0037963dcd9cc79f04fcba25ccc08 Mon Sep 17 00:00:00 2001 From: Matt Hansen Date: Sat, 20 Feb 2016 19:24:20 -0800 Subject: [PATCH 010/124] Update README.md --- camera/README.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/camera/README.md b/camera/README.md index dc48fcfd7f..e4a85fd438 100644 --- a/camera/README.md +++ b/camera/README.md @@ -8,7 +8,7 @@ * Make sure that the software stack is installed properly and that the camera is working. This can be checked by connecting the camera to a USB3 port and running the "cpp-capture" sample program in the "librealsense/bin" folder. If this does not work, you should first fix this issue before continuing with the ROS integration. * Make sure "/usr/local/lib" is set in your "LD_LIBRARY_PATH". -* Copy the librealsense header files folder "librealsense/include/librealsense" to "/usr/local/include". +* Copy the librealsense header files **folder** "librealsense/include/librealsense" to "/usr/local/include". #####Building package: @@ -127,7 +127,7 @@ Infrared2 camera Use the following command to launch the camera nodelet. You will notice the camera light up. - $ roslaunch realsense_camera realsense_r200_launch_preset.launch + $ roslaunch realsense_camera realsense_r200_nodelet_standalone_preset.launch View using RVIZ: From be41ed2855b918c2cf8ca3e331efae684243784d Mon Sep 17 00:00:00 2001 From: Mark D Horn Date: Mon, 22 Feb 2016 19:25:56 -0700 Subject: [PATCH 011/124] Enable Defensive Compile Flags --- camera/CMakeLists.txt | 11 ++++++++++- 1 file changed, 10 insertions(+), 1 deletion(-) diff --git a/camera/CMakeLists.txt b/camera/CMakeLists.txt index 99ae8cf90f..241bff20a6 100644 --- a/camera/CMakeLists.txt +++ b/camera/CMakeLists.txt @@ -2,7 +2,16 @@ cmake_minimum_required(VERSION 2.8.3) project(realsense_camera) -set(CMAKE_CXX_FLAGS "-std=c++11 ${CMAKE_CXX_FLAGS}") +# Save the command line compile commands in the build output +set(CMAKE_EXPORT_COMPILE_COMMANDS 1) +# View the makefile commands during build +#set(CMAKE_VERBOSE_MAKEFILE on) + +set(CMAKE_CXX_FLAGS "-fPIE -fPIC -std=c++11 -O2 -D_FORTIFY_SOURCE=2 -fstack-protector -Wformat -Wformat-security -Wall ${CMAKE_CXX_FLAGS}") +# Flags executables +set(CMAKE_EXE_LINKER_FLAGS "-pie -z noexecstack -z relro -z now") +# Flags shared libraries +set(CMAKE_SHARED_LINKER_FLAGS "-z noexecstack -z relro -z now") find_package(catkin REQUIRED COMPONENTS roscpp From f846b1ae9e160ff4b52fb27e8e4f5444c1fa917a Mon Sep 17 00:00:00 2001 From: Matthew Hansen Date: Tue, 23 Feb 2016 11:07:31 -0800 Subject: [PATCH 012/124] Fix compiler warnings in nodelet and test --- camera/src/realsense_camera_nodelet.cpp | 5 +++-- camera/test/realsense_camera_test_node.cpp | 12 +++++------- 2 files changed, 8 insertions(+), 9 deletions(-) diff --git a/camera/src/realsense_camera_nodelet.cpp b/camera/src/realsense_camera_nodelet.cpp index 99a81d64a1..baf158ceeb 100644 --- a/camera/src/realsense_camera_nodelet.cpp +++ b/camera/src/realsense_camera_nodelet.cpp @@ -475,6 +475,9 @@ namespace realsense_camera image_[(uint32_t) RS_STREAM_INFRARED2].data = (unsigned char *) (rs_get_frame_data (rs_device_, RS_STREAM_INFRARED2, 0)); break; + default: + // no other streams supported + break; } } @@ -586,8 +589,6 @@ namespace realsense_camera sensor_msgs::PointCloud2Iterator < uint8_t > iter_g (msg_pointcloud, "g"); sensor_msgs::PointCloud2Iterator < uint8_t > iter_b (msg_pointcloud, "b"); - rs::float2 thirdImagePixel; - float depth_point[3], color_point[3], color_pixel[2], scaled_depth; unsigned char *color_data = image_color.data; const float depth_scale = rs_get_device_depth_scale (rs_device_, &rs_error_); diff --git a/camera/test/realsense_camera_test_node.cpp b/camera/test/realsense_camera_test_node.cpp index abf88eef1c..ef86816fc9 100644 --- a/camera/test/realsense_camera_test_node.cpp +++ b/camera/test/realsense_camera_test_node.cpp @@ -18,7 +18,7 @@ void imageInfrared1Callback(const sensor_msgs::ImageConstPtr & msg, const sensor long infrared1_total = 0; int infrared1_count = 1; - for (int i = 0; i < msg->height * msg->width; i++) + for (unsigned int i = 0; i < msg->height * msg->width; i++) { if (*infrared1_data > 0 && *infrared1_data < 255) { @@ -48,7 +48,7 @@ void imageInfrared2Callback(const sensor_msgs::ImageConstPtr & msg, const sensor long infrared2_total = 0; int infrared2_count = 1; - for (int i = 0; i < msg->height * msg->width; i++) + for (unsigned int i = 0; i < msg->height * msg->width; i++) { if (*infrared2_data > 0 && *infrared2_data < 255) { @@ -77,9 +77,9 @@ void imageDepthCallback(const sensor_msgs::ImageConstPtr & msg, const sensor_msg long depth_total = 0; int depth_count = 0; - for (int i = 0; i < msg->height * msg->width; ++i) + for (unsigned int i = 0; i < msg->height * msg->width; ++i) { - if (0 < *image_data <= R200_DEPTH_MAX) + if ((0 < *image_data) && (*image_data <= R200_DEPTH_MAX)) { depth_total += *image_data; depth_count++; @@ -139,7 +139,7 @@ void imageColorCallback(const sensor_msgs::ImageConstPtr & msg, const sensor_msg uchar *color_data = image.data; long color_total = 0; int color_count = 1; - for (int i = 0; i < msg->height * msg->width * 3; i++) + for (unsigned int i = 0; i < msg->height * msg->width * 3; i++) { if (*color_data > 0 && *color_data < 255) { @@ -452,8 +452,6 @@ void fillConfigMap(int argc, char **argv) int main(int argc, char **argv) { - int return_value = 1; - testing::InitGoogleTest(&argc, argv); ros::init(argc, argv, "utest"); fillConfigMap(argc, argv); From 6a31b7f753c6fc92243d804a822137faffe76be0 Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Thu, 18 Feb 2016 16:33:53 -0800 Subject: [PATCH 013/124] Renamed contents of launch files to meet rgbd launch standards. Included rviz config file for testing. --- camera/launch/realsense_r200_nodelet.launch | 2 +- camera/package.xml | 2 +- camera/rviz/realsenseRvizConfiguration3.rviz | 305 ++++++++++++++++++ ...l => realsense_camera_nodelet_plugins.xml} | 0 4 files changed, 307 insertions(+), 2 deletions(-) create mode 100644 camera/rviz/realsenseRvizConfiguration3.rviz rename camera/src/{RealsenseNodelet_plugins.xml => realsense_camera_nodelet_plugins.xml} (100%) diff --git a/camera/launch/realsense_r200_nodelet.launch b/camera/launch/realsense_r200_nodelet.launch index 9bc1944bb0..c292c6bf9b 100644 --- a/camera/launch/realsense_r200_nodelet.launch +++ b/camera/launch/realsense_r200_nodelet.launch @@ -7,7 +7,7 @@ - diff --git a/camera/package.xml b/camera/package.xml index 1033ead43f..904e0cfdd1 100644 --- a/camera/package.xml +++ b/camera/package.xml @@ -40,7 +40,7 @@ pcl_ros - + diff --git a/camera/rviz/realsenseRvizConfiguration3.rviz b/camera/rviz/realsenseRvizConfiguration3.rviz new file mode 100644 index 0000000000..be9c8f7197 --- /dev/null +++ b/camera/rviz/realsenseRvizConfiguration3.rviz @@ -0,0 +1,305 @@ +Panels: + - Class: rviz/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: + - /Global Options1 + - /Status1 + - /Image5 + - /Image6 + - /Image7 + - /Image9 + Splitter Ratio: 0.5 + Tree Height: 775 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.588679 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: Image +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.03 + 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 + - Class: rviz/Image + Enabled: true + Image Topic: /camera/rgb/image_mono + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: true + Queue Size: 2 + Transport Hint: raw + Value: true + - Class: rviz/Image + Enabled: true + Image Topic: /camera/rgb/image_color + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: true + Queue Size: 2 + Transport Hint: raw + Value: true + - Class: rviz/Image + Enabled: false + Image Topic: /camera/rgb/image_rect_mono + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: true + Queue Size: 2 + Transport Hint: raw + Value: false + - Class: rviz/Image + Enabled: false + Image Topic: /camera/rgb/image_rect_color + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: true + Queue Size: 2 + Transport Hint: raw + Value: false + - Class: rviz/Image + Enabled: true + Image Topic: /camera/depth/image_rect_raw + Max Value: 3500 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: false + Queue Size: 2 + Transport Hint: raw + Value: true + - Class: rviz/Image + Enabled: true + Image Topic: /camera/depth/image_rect + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: false + Queue Size: 2 + Transport Hint: raw + Value: true + - Class: rviz/Image + Enabled: true + Image Topic: /camera/depth/image + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: false + Queue Size: 2 + Transport Hint: raw + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: Intensity + 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: PointCloud2 + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.01 + Style: Flat Squares + Topic: /camera/depth/points + Use Fixed Frame: true + Use rainbow: true + Value: true + - Class: rviz/Image + Enabled: false + Image Topic: /camera/ir/image_rect_ir + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: true + Queue Size: 2 + Transport Hint: raw + Value: false + - Class: rviz/Image + Enabled: true + Image Topic: /camera/depth_registered/sw_registered/image_rect_raw + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: true + Queue Size: 2 + Transport Hint: raw + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: "" + 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: PointCloud2 + Position Transformer: "" + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.01 + Style: Flat Squares + Topic: /camera/depth_registered/points + Use Fixed Frame: true + Use rainbow: true + Value: true + - Class: rviz/Image + Enabled: true + Image Topic: /camera/depth_registered/sw_registered/image_rect + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: true + Queue Size: 2 + Transport Hint: raw + Value: true + - Class: rviz/Image + Enabled: false + Image Topic: /camera/depth_registered/hw_registered/image_rect + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: true + Queue Size: 2 + Transport Hint: raw + Value: false + - Class: rviz/Image + Enabled: false + Image Topic: /camera/depth_registered/image + Max Value: 1 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: true + Queue Size: 2 + Transport Hint: raw + Value: false + Enabled: true + Global Options: + Background Color: 48; 48; 48 + 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 + Topic: /initialpose + - 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: 12.544 + Enable Stereo Rendering: + Stereo Eye Separation: 0.06 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: 0 + Y: 0 + Z: 0 + Name: Current View + Near Clip Distance: 0.01 + Pitch: 1.5598 + Target Frame: + Value: Orbit (rviz) + Yaw: 1.5954 + Saved: ~ +Window Geometry: + Displays: + collapsed: false + Height: 1056 + Hide Left Dock: false + Hide Right Dock: false + Image: + collapsed: false + QMainWindow State: 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 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1855 + X: 55 + Y: -14 diff --git a/camera/src/RealsenseNodelet_plugins.xml b/camera/src/realsense_camera_nodelet_plugins.xml similarity index 100% rename from camera/src/RealsenseNodelet_plugins.xml rename to camera/src/realsense_camera_nodelet_plugins.xml From d1eded04968e01c9fa2ea33fe1bc6b06cbbbb6fd Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Thu, 18 Feb 2016 20:56:23 -0800 Subject: [PATCH 014/124] Updated code to refer to color_frame_id as rgb_frame_id based on rgbd_launch standards. Updated launch file to remap camera_info topic names. --- camera/launch/realsense_r200_nodelet.launch | 7 +++++-- camera/launch/realsense_r200_rgbd.launch | 2 +- camera/src/realsense_camera_nodelet.cpp | 4 ++-- 3 files changed, 8 insertions(+), 5 deletions(-) diff --git a/camera/launch/realsense_r200_nodelet.launch b/camera/launch/realsense_r200_nodelet.launch index c292c6bf9b..2da64ec90b 100644 --- a/camera/launch/realsense_r200_nodelet.launch +++ b/camera/launch/realsense_r200_nodelet.launch @@ -15,7 +15,10 @@ - + + + + + - diff --git a/camera/launch/realsense_r200_rgbd.launch b/camera/launch/realsense_r200_rgbd.launch index 137ca0c354..ea3cd853b2 100644 --- a/camera/launch/realsense_r200_rgbd.launch +++ b/camera/launch/realsense_r200_rgbd.launch @@ -21,7 +21,7 @@ tree. Useful if you are playing back recorded raw data from a bag, or are supplying a more accurate tf tree from calibration. --> - + diff --git a/camera/src/realsense_camera_nodelet.cpp b/camera/src/realsense_camera_nodelet.cpp index baf158ceeb..e8c4f7e127 100644 --- a/camera/src/realsense_camera_nodelet.cpp +++ b/camera/src/realsense_camera_nodelet.cpp @@ -387,9 +387,9 @@ namespace realsense_camera frame_id_[RS_STREAM_DEPTH] = config_.at ("depth_frame_id").c_str (); } - if (config_.find ("color_frame_id") != config_.end ()) + if (config_.find ("rgb_frame_id") != config_.end ()) { - frame_id_[RS_STREAM_COLOR] = config_.at ("color_frame_id").c_str (); + frame_id_[RS_STREAM_COLOR] = config_.at ("rgb_frame_id").c_str (); } if (mode_.compare ("manual") == 0) From 8e3ef3862ba52b6395c0dc68a35bfb3d4312106f Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Mon, 22 Feb 2016 18:46:36 -0800 Subject: [PATCH 015/124] Updated launch file to remap pointcloud topic name according to rgbd standards. --- camera/launch/realsense_r200_nodelet.launch | 1 + 1 file changed, 1 insertion(+) diff --git a/camera/launch/realsense_r200_nodelet.launch b/camera/launch/realsense_r200_nodelet.launch index 2da64ec90b..bbc1239f4b 100644 --- a/camera/launch/realsense_r200_nodelet.launch +++ b/camera/launch/realsense_r200_nodelet.launch @@ -16,6 +16,7 @@ + From 6df42a8987678fedccfd76aa7f4dada67b071e6f Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Mon, 22 Feb 2016 20:08:44 -0800 Subject: [PATCH 016/124] Updated fix for following bugs: RAR-224, RAR-223, RAR-225, RAR-237. Also removed org.eclipse.cdt.ui.prefs file based on Protex scan result. --- camera/.settings/org.eclipse.cdt.ui.prefs | 2 -- camera/README.md | 10 ++++++---- 2 files changed, 6 insertions(+), 6 deletions(-) delete mode 100644 camera/.settings/org.eclipse.cdt.ui.prefs diff --git a/camera/.settings/org.eclipse.cdt.ui.prefs b/camera/.settings/org.eclipse.cdt.ui.prefs deleted file mode 100644 index 4ee12a4ba7..0000000000 --- a/camera/.settings/org.eclipse.cdt.ui.prefs +++ /dev/null @@ -1,2 +0,0 @@ -eclipse.preferences.version=1 -formatter_settings_version=1 diff --git a/camera/README.md b/camera/README.md index e4a85fd438..df2a9b0bd8 100644 --- a/camera/README.md +++ b/camera/README.md @@ -8,7 +8,9 @@ * Make sure that the software stack is installed properly and that the camera is working. This can be checked by connecting the camera to a USB3 port and running the "cpp-capture" sample program in the "librealsense/bin" folder. If this does not work, you should first fix this issue before continuing with the ROS integration. * Make sure "/usr/local/lib" is set in your "LD_LIBRARY_PATH". -* Copy the librealsense header files **folder** "librealsense/include/librealsense" to "/usr/local/include". +* Copy the librealsense header files folder "librealsense/include/librealsense" to "/usr/local/include". + + E.g. sudo cp -r /include/librealsense /usr/local/include #####Building package: @@ -179,8 +181,8 @@ The Unit Tests can be executed using either of the methods: Using rostest command with test files - $ rostest - E.g. rostest realsense_r200_depth_only.test + $ rostest realsense_camera + E.g. rostest realsense_camera realsense_r200_depth_only.test Using rosrun command @@ -189,7 +191,7 @@ Using rosrun command $ rosrun realsense_camera realsense_camera_test E.g. rosrun realsense_camera realsense_camera_test enable_depth 1 depth_encoding 16UC1 depth_height 360 depth_width 480 depth_step 960 enable_color 1 color_encoding rgb8 color_height 480 color_width 640 color_step 1920 -Sample testfiles are available in test directory +Sample test files are available in test directory realsense_r200_color_only.test From 7789dc457a9d770a46b8bad15e41aad37b5beedb Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Tue, 23 Feb 2016 13:25:06 -0800 Subject: [PATCH 017/124] Based on the rgbd_launch standards, modified the main code, test code, launch files and test files to use true and false instead of 1 and 0. --- camera/launch/realsense_r200_nodelet.launch | 33 +++++++++++-------- ...ense_r200_nodelet_standalone_manual.launch | 6 ++-- ...ense_r200_nodelet_standalone_preset.launch | 6 ++-- ...se_r200_nodelet_standalone_settings.launch | 6 ++-- camera/launch/realsense_r200_rgbd.launch | 5 ++- camera/src/realsense_camera_nodelet.cpp | 29 +++++++++++++--- camera/test/realsense_camera_test_node.cpp | 18 ++++++++-- camera/test/realsense_r200_color_only.test | 4 +-- camera/test/realsense_r200_depth_only.test | 4 +-- camera/test/realsense_r200_settings.test | 6 ++-- 10 files changed, 81 insertions(+), 36 deletions(-) diff --git a/camera/launch/realsense_r200_nodelet.launch b/camera/launch/realsense_r200_nodelet.launch index bbc1239f4b..5ff3f4ee9e 100644 --- a/camera/launch/realsense_r200_nodelet.launch +++ b/camera/launch/realsense_r200_nodelet.launch @@ -1,25 +1,32 @@ - - - - - - - + + + + + + + + + + + - + rgb_frame_id $(arg rgb_frame_id) + enable_depth $(arg enable_depth) + enable_color $(arg enable_color) + enable_pointcloud $(arg enable_pointcloud)"> + - - - - + + + + diff --git a/camera/launch/realsense_r200_nodelet_standalone_manual.launch b/camera/launch/realsense_r200_nodelet_standalone_manual.launch index f931bdab64..519fbcf0b1 100644 --- a/camera/launch/realsense_r200_nodelet_standalone_manual.launch +++ b/camera/launch/realsense_r200_nodelet_standalone_manual.launch @@ -5,9 +5,9 @@ - - - + + + diff --git a/camera/launch/realsense_r200_nodelet_standalone_preset.launch b/camera/launch/realsense_r200_nodelet_standalone_preset.launch index 42029217ca..39ef3a29ab 100644 --- a/camera/launch/realsense_r200_nodelet_standalone_preset.launch +++ b/camera/launch/realsense_r200_nodelet_standalone_preset.launch @@ -1,9 +1,9 @@ - - - + + + diff --git a/camera/launch/realsense_r200_nodelet_standalone_settings.launch b/camera/launch/realsense_r200_nodelet_standalone_settings.launch index 675c9c7ba3..1f889ee666 100644 --- a/camera/launch/realsense_r200_nodelet_standalone_settings.launch +++ b/camera/launch/realsense_r200_nodelet_standalone_settings.launch @@ -1,8 +1,8 @@ - - - + + + diff --git a/camera/launch/realsense_r200_rgbd.launch b/camera/launch/realsense_r200_rgbd.launch index ea3cd853b2..6a01af3827 100644 --- a/camera/launch/realsense_r200_rgbd.launch +++ b/camera/launch/realsense_r200_rgbd.launch @@ -60,7 +60,10 @@ - + + + + diff --git a/camera/src/realsense_camera_nodelet.cpp b/camera/src/realsense_camera_nodelet.cpp index e8c4f7e127..69525963a8 100644 --- a/camera/src/realsense_camera_nodelet.cpp +++ b/camera/src/realsense_camera_nodelet.cpp @@ -364,17 +364,38 @@ namespace realsense_camera if (config_.find ("enable_color") != config_.end ()) { - enable_color_ = atoi (config_.at ("enable_color").c_str ()); + if (strcmp((config_.at ("enable_color").c_str ()),"true") == 0) + { + enable_color_ = true; + } + else + { + enable_color_ = false; + } } if (config_.find ("enable_depth") != config_.end ()) { - enable_depth_ = atoi (config_.at ("enable_depth").c_str ()); + if (strcmp((config_.at ("enable_depth").c_str ()),"true") == 0) + { + enable_depth_ = true; + } + else + { + enable_depth_ = false; + } } - if (config_.find ("enable_pointCloud") != config_.end ()) + if (config_.find ("enable_pointcloud") != config_.end ()) { - enable_pointcloud_ = atoi (config_.at ("enable_pointCloud").c_str ()); + if (strcmp((config_.at ("enable_pointcloud").c_str ()),"true") == 0) + { + enable_pointcloud_ = true; + } + else + { + enable_pointcloud_ = false; + } } if (config_.find ("camera") != config_.end ()) diff --git a/camera/test/realsense_camera_test_node.cpp b/camera/test/realsense_camera_test_node.cpp index ef86816fc9..b37b12e524 100644 --- a/camera/test/realsense_camera_test_node.cpp +++ b/camera/test/realsense_camera_test_node.cpp @@ -398,7 +398,14 @@ void fillConfigMap(int argc, char **argv) if (config_args.find("enable_depth") != config_args.end()) { ROS_INFO ("RealSense Camera - Setting %s to %s", "enable_depth", config_args.at("enable_depth").c_str()); - enable_depth = atoi(config_args.at("enable_depth").c_str()); + if (strcmp((config_args.at("enable_depth").c_str ()),"true") == 0) + { + enable_depth = true; + } + else + { + enable_depth = false; + } } if (config_args.find("depth_encoding") != config_args.end()) { @@ -425,7 +432,14 @@ void fillConfigMap(int argc, char **argv) if (config_args.find("enable_color") != config_args.end()) { ROS_INFO ("RealSense Camera - Setting %s to %s", "enable_color", config_args.at("enable_color").c_str()); - enable_color = atoi(config_args.at("enable_color").c_str()); + if (strcmp((config_args.at("enable_color").c_str ()),"true") == 0) + { + enable_color = true; + } + else + { + enable_color = false; + } } if (config_args.find("color_encoding") != config_args.end()) { diff --git a/camera/test/realsense_r200_color_only.test b/camera/test/realsense_r200_color_only.test index 1d6cbc71fb..99150176ac 100644 --- a/camera/test/realsense_r200_color_only.test +++ b/camera/test/realsense_r200_color_only.test @@ -1,10 +1,10 @@ - + + args="enable_depth false enable_color true" /> diff --git a/camera/test/realsense_r200_depth_only.test b/camera/test/realsense_r200_depth_only.test index 79f0afe71c..66423cc13e 100644 --- a/camera/test/realsense_r200_depth_only.test +++ b/camera/test/realsense_r200_depth_only.test @@ -1,10 +1,10 @@ - + + args="enable_depth true enable_color false" /> diff --git a/camera/test/realsense_r200_settings.test b/camera/test/realsense_r200_settings.test index 6ad0ed7888..c74383f288 100644 --- a/camera/test/realsense_r200_settings.test +++ b/camera/test/realsense_r200_settings.test @@ -1,8 +1,8 @@ - - - + + + From cde43bec95bb59bc33b4793409ce13455550d561 Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Tue, 23 Feb 2016 15:04:31 -0800 Subject: [PATCH 018/124] Resolved rebase conflict. --- camera/README.md | 1 + 1 file changed, 1 insertion(+) diff --git a/camera/README.md b/camera/README.md index df2a9b0bd8..2041e7914c 100644 --- a/camera/README.md +++ b/camera/README.md @@ -12,6 +12,7 @@ If this does not work, you should first fix this issue before continuing with th E.g. sudo cp -r /include/librealsense /usr/local/include + #####Building package: * Setup ROS and create a local catkin workspace. From 0384e9c9da6b0882304e2a5455dfad19d0036c06 Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Tue, 23 Feb 2016 20:13:51 -0800 Subject: [PATCH 019/124] RAR-186 Added rgbd unit test artifacts. Updated make file with rgbd unit test executable. --- camera/CMakeLists.txt | 7 + .../test/realsense_camera_test_rgbd_node.cpp | 202 ++++++++++++++++++ camera/test/realsense_camera_test_rgbd_node.h | 38 ++++ camera/test/realsense_r200_rgbd.test | 8 + 4 files changed, 255 insertions(+) create mode 100644 camera/test/realsense_camera_test_rgbd_node.cpp create mode 100644 camera/test/realsense_camera_test_rgbd_node.h create mode 100644 camera/test/realsense_r200_rgbd.test diff --git a/camera/CMakeLists.txt b/camera/CMakeLists.txt index 241bff20a6..7c12c647bb 100644 --- a/camera/CMakeLists.txt +++ b/camera/CMakeLists.txt @@ -54,3 +54,10 @@ target_link_libraries(realsense_camera_test ${GTEST_LIBRARIES} ) add_dependencies(realsense_camera_test realsense_camera_generate_messages_cpp) + +add_executable(realsense_camera_test_rgbd test/realsense_camera_test_rgbd_node.cpp) +target_link_libraries(realsense_camera_test_rgbd + ${catkin_LIBRARIES} + ${GTEST_LIBRARIES} +) +add_dependencies(realsense_camera_test_rgbd realsense_camera_generate_messages_cpp) diff --git a/camera/test/realsense_camera_test_rgbd_node.cpp b/camera/test/realsense_camera_test_rgbd_node.cpp new file mode 100644 index 0000000000..20e7dfafd2 --- /dev/null +++ b/camera/test/realsense_camera_test_rgbd_node.cpp @@ -0,0 +1,202 @@ +#include "realsense_camera_test_rgbd_node.h" +using namespace std; + +void topic0Callback(const sensor_msgs::ImageConstPtr msg) +{ + if ((msg->height != 0) && (msg->width != 0)) + { + topic_0_recv = true; + } +} + +void topic1Callback(const sensor_msgs::ImageConstPtr msg) +{ + if ((msg->height != 0) && (msg->width != 0)) + { + topic_1_recv = true; + } +} + +void topic2Callback(const sensor_msgs::ImageConstPtr msg) +{ + if ((msg->height != 0) && (msg->width != 0)) + { + topic_2_recv = true; + } +} + +void topic3Callback(const sensor_msgs::ImageConstPtr msg) +{ + if ((msg->height != 0) && (msg->width != 0)) + { + topic_3_recv = true; + } +} + +void topic4Callback(const sensor_msgs::ImageConstPtr msg) +{ + if ((msg->height != 0) && (msg->width != 0)) + { + topic_4_recv = true; + } +} + +void topic5Callback(const sensor_msgs::ImageConstPtr msg) +{ + if ((msg->height != 0) && (msg->width != 0)) + { + topic_5_recv = true; + } +} + +void topic6Callback(const sensor_msgs::ImageConstPtr msg) +{ + if ((msg->height != 0) && (msg->width != 0)) + { + topic_6_recv = true; + } +} + +void topic7Callback(const sensor_msgs::PointCloud2ConstPtr msg) +{ + if ((msg->height != 0) && (msg->width != 0)) + { + topic_7_recv = true; + } +} + +void topic8Callback(const sensor_msgs::ImageConstPtr msg) +{ + if ((msg->height != 0) && (msg->width != 0)) + { + topic_8_recv = true; + } +} + +void topic9Callback(const sensor_msgs::ImageConstPtr msg) +{ + if ((msg->height != 0) && (msg->width != 0)) + { + topic_9_recv = true; + } +} + +void topic10Callback(const sensor_msgs::CameraInfoConstPtr msg) +{ + if ((msg->height != 0) && (msg->width != 0)) + { + topic_10_recv = true; + } +} + +void topic11Callback(const sensor_msgs::PointCloud2ConstPtr msg) +{ + if ((msg->height != 0) && (msg->width != 0)) + { + topic_11_recv = true; + } +} + +void topic12Callback(const sensor_msgs::ImageConstPtr msg) +{ + if ((msg->height != 0) && (msg->width != 0)) + { + topic_12_recv = true; + } +} + +TEST (RealsenseTests, RGB_IMAGE_MONO) +{ + EXPECT_TRUE (topic_0_recv); +} + +TEST (RealsenseTests, RGB_IMAGE_COLOR) +{ + EXPECT_TRUE (topic_1_recv); +} + +TEST (RealsenseTests, RGB_IMAGE_RECT_MONO) +{ + EXPECT_TRUE (topic_2_recv); +} + +TEST (RealsenseTests, RGB_IMAGE_RECT_COLOR) +{ + EXPECT_TRUE (topic_3_recv); +} + +TEST (RealsenseTests, DEPTH_IMAGE_RECT_RAW) +{ + EXPECT_TRUE (topic_4_recv); +} + +TEST (RealsenseTests, DEPTH_IMAGE_RECT) +{ + EXPECT_TRUE (topic_5_recv); +} + +TEST (RealsenseTests, DEPTH_IMAGE) +{ + EXPECT_TRUE (topic_6_recv); +} + +TEST (RealsenseTests, DEPTH_POINTS) +{ + EXPECT_TRUE (topic_7_recv); +} + +TEST (RealsenseTests, IR_IMAGE_RECT_IR) +{ + EXPECT_TRUE (topic_8_recv); +} + +TEST (RealsenseTests, DEPTH_REG_SW_REG_IMAGE_RECT_RAW) +{ + EXPECT_TRUE (topic_9_recv); +} + +TEST (RealsenseTests, DEPTH_REG_SW_REG_CAMERA_INFO) +{ + EXPECT_TRUE (topic_10_recv); +} + +TEST (RealsenseTests, DEPTH_REG_POINTS) +{ + EXPECT_TRUE (topic_11_recv); +} + +TEST (RealsenseTests, DEPTH_REG_SW_REG_IMAGE_RECT) +{ + EXPECT_TRUE (topic_12_recv); +} + +int main(int argc, char **argv) +{ + testing::InitGoogleTest(&argc, argv); + ros::init(argc, argv, "utest"); + + ROS_INFO_STREAM("RealSense Camera - Starting rgbd_launch Tests..."); + + ros::NodeHandle nh; + + subscriber[0] = nh.subscribe < sensor_msgs::Image > (RGB_IMAGE_MONO, 1, topic0Callback, 0); + subscriber[1] = nh.subscribe < sensor_msgs::Image > (RGB_IMAGE_COLOR, 1, topic1Callback, 0); + subscriber[2] = nh.subscribe < sensor_msgs::Image > (RGB_IMAGE_RECT_MONO, 1, topic2Callback, 0); + subscriber[3] = nh.subscribe < sensor_msgs::Image > (RGB_IMAGE_RECT_COLOR, 1, topic3Callback, 0); + subscriber[4] = nh.subscribe < sensor_msgs::Image > (DEPTH_IMAGE_RECT_RAW, 1, topic4Callback, 0); + subscriber[5] = nh.subscribe < sensor_msgs::Image > (DEPTH_IMAGE_RECT, 1, topic5Callback, 0); + subscriber[6] = nh.subscribe < sensor_msgs::Image > (DEPTH_IMAGE, 1, topic6Callback, 0); + subscriber[7] = nh.subscribe < sensor_msgs::PointCloud2 > (DEPTH_POINTS, 1, topic7Callback); + subscriber[8] = nh.subscribe < sensor_msgs::Image > (IR_IMAGE_RECT_IR, 1, topic8Callback, 0); + subscriber[9] = nh.subscribe < sensor_msgs::Image > (DEPTH_REG_SW_REG_IMAGE_RECT_RAW, 1, topic9Callback, 0); + subscriber[10] = nh.subscribe < sensor_msgs::CameraInfo > (DEPTH_REG_SW_REG_CAMERA_INFO, 1, topic10Callback); + subscriber[11] = nh.subscribe < sensor_msgs::PointCloud2 > (DEPTH_REG_POINTS, 1, topic11Callback, 0); + subscriber[12] = nh.subscribe < sensor_msgs::Image > (DEPTH_REG_SW_REG_IMAGE_RECT, 1, topic12Callback, 0); + + ros::Duration duration; + duration.sec = 10; + duration.sleep(); + ros::spinOnce(); + + return RUN_ALL_TESTS(); +} diff --git a/camera/test/realsense_camera_test_rgbd_node.h b/camera/test/realsense_camera_test_rgbd_node.h new file mode 100644 index 0000000000..78a44b3ea0 --- /dev/null +++ b/camera/test/realsense_camera_test_rgbd_node.h @@ -0,0 +1,38 @@ +#include +#include +#include +#include +#include +#include + +const static int TOPIC_COUNT = 13; + +const char *RGB_IMAGE_MONO = "/camera/rgb/image_mono"; +const char *RGB_IMAGE_COLOR = "/camera/rgb/image_color"; +const char *RGB_IMAGE_RECT_MONO = "/camera/rgb/image_rect_mono"; +const char *RGB_IMAGE_RECT_COLOR = "/camera/rgb/image_rect_color"; +const char *DEPTH_IMAGE_RECT_RAW = "/camera/depth/image_rect_raw"; +const char *DEPTH_IMAGE_RECT = "/camera/depth/image_rect"; +const char *DEPTH_IMAGE = "/camera/depth/image"; +const char *DEPTH_POINTS = "/camera/depth/points"; +const char *IR_IMAGE_RECT_IR = "/camera/ir/image_rect_ir"; +const char *DEPTH_REG_SW_REG_IMAGE_RECT_RAW = "/camera/depth_registered/sw_registered/image_rect_raw"; +const char *DEPTH_REG_SW_REG_CAMERA_INFO = "/camera/depth_registered/sw_registered/camera_info"; +const char *DEPTH_REG_POINTS = "/camera/depth_registered/points"; +const char *DEPTH_REG_SW_REG_IMAGE_RECT = "/camera/depth_registered/sw_registered/image_rect"; + +bool topic_0_recv = false; +bool topic_1_recv = false; +bool topic_2_recv = false; +bool topic_3_recv = false; +bool topic_4_recv = false; +bool topic_5_recv = false; +bool topic_6_recv = false; +bool topic_7_recv = false; +bool topic_8_recv = false; +bool topic_9_recv = false; +bool topic_10_recv = false; +bool topic_11_recv = false; +bool topic_12_recv = false; + +ros::Subscriber subscriber[TOPIC_COUNT]; diff --git a/camera/test/realsense_r200_rgbd.test b/camera/test/realsense_r200_rgbd.test new file mode 100644 index 0000000000..e7ae01897e --- /dev/null +++ b/camera/test/realsense_r200_rgbd.test @@ -0,0 +1,8 @@ + + + + + + + + From 2bd89377a3f1cee45e28d3c7ecf0c297615846ed Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Tue, 23 Feb 2016 21:30:41 -0800 Subject: [PATCH 020/124] Modified rgbd launch and test files to handle enable_ir flag. --- camera/launch/realsense_r200_nodelet.launch | 62 ++++++++++++--------- camera/launch/realsense_r200_rgbd.launch | 22 ++++---- camera/test/realsense_r200_rgbd.test | 12 ++-- 3 files changed, 52 insertions(+), 44 deletions(-) diff --git a/camera/launch/realsense_r200_nodelet.launch b/camera/launch/realsense_r200_nodelet.launch index 5ff3f4ee9e..410fe91ca8 100644 --- a/camera/launch/realsense_r200_nodelet.launch +++ b/camera/launch/realsense_r200_nodelet.launch @@ -1,32 +1,40 @@ - - - - - - - - - - - - - + + + + + + + + + + + + + + + + + + - - - - - - - - - - - + enable_depth $(arg enable_depth_ir) + enable_color $(arg enable_color) + enable_pointcloud $(arg enable_pointcloud)"> + + + + + + + + + + + diff --git a/camera/launch/realsense_r200_rgbd.launch b/camera/launch/realsense_r200_rgbd.launch index 6a01af3827..32a5c736c0 100644 --- a/camera/launch/realsense_r200_rgbd.launch +++ b/camera/launch/realsense_r200_rgbd.launch @@ -3,9 +3,9 @@ - - - + + + @@ -32,9 +32,8 @@ - - - + + @@ -53,7 +52,7 @@ + file="$(find realsense_camera)/launch/realsense_r200_nodelet.launch"> @@ -63,9 +62,10 @@ - + + - + @@ -84,12 +84,12 @@ - + + file="$(find rgbd_launch)/launch/kinect_frames.launch"> diff --git a/camera/test/realsense_r200_rgbd.test b/camera/test/realsense_r200_rgbd.test index e7ae01897e..8832e12d12 100644 --- a/camera/test/realsense_r200_rgbd.test +++ b/camera/test/realsense_r200_rgbd.test @@ -1,8 +1,8 @@ - - - - - + + + + + - + From e465c56a6d82ee89fe40a53353270cc6161ecd2f Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Tue, 23 Feb 2016 21:59:35 -0800 Subject: [PATCH 021/124] Updated README file to indicate that the camera does not provide hardware based depth registration/projector data. --- camera/README.md | 12 ++++++++++++ 1 file changed, 12 insertions(+) diff --git a/camera/README.md b/camera/README.md index 2041e7914c..22e648e15a 100644 --- a/camera/README.md +++ b/camera/README.md @@ -28,6 +28,16 @@ Sample launch files are available in camera/launch directory realsense_r200_rgbd.launch +Note: The camera does not provide hardware based depth registration/projector data. Hence the launch file realsense_r200_rgbd.launch will not generate data for the following topics: + +/camera/depth_registered/hw_registered/image_rect_raw +/camera/depth_registered/points +/camera/depth_registered/hw_registered/image_rect +/camera/depth_registered/image +/camera/depth/disparity +/camera/depth_registered/disparity + + ### Intel® RealSense™ R200 Nodelet Publishing stream data from the Intel® RealSense™ R200 (DS4) camera @@ -202,6 +212,8 @@ Sample test files are available in test directory realsense_r200_settings.test +realsense_r200_rgbd.test + Both of these methods first starts "RealsenseNodelet" for Intel® RealSense™ R200 (DS4) camera and then executes all the unit tests. ###Limitations: From a4070201d35dcef4dd59004ad73fb8b0509378e0 Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Tue, 23 Feb 2016 22:17:43 -0800 Subject: [PATCH 022/124] RAR-234 Update API documentation. --- camera/README.md | 20 ++++++++++++-------- 1 file changed, 12 insertions(+), 8 deletions(-) diff --git a/camera/README.md b/camera/README.md index 22e648e15a..cd369e848c 100644 --- a/camera/README.md +++ b/camera/README.md @@ -28,14 +28,13 @@ Sample launch files are available in camera/launch directory realsense_r200_rgbd.launch -Note: The camera does not provide hardware based depth registration/projector data. Hence the launch file realsense_r200_rgbd.launch will not generate data for the following topics: - -/camera/depth_registered/hw_registered/image_rect_raw -/camera/depth_registered/points -/camera/depth_registered/hw_registered/image_rect -/camera/depth_registered/image -/camera/depth/disparity -/camera/depth_registered/disparity +Note: The camera does not provide hardware based depth registration/projector data. Hence the launch file "realsense_r200_rgbd.launch" will not generate data for the following topics: +/camera/depth_registered/hw_registered/image_rect_raw +/camera/depth_registered/points +/camera/depth_registered/hw_registered/image_rect +/camera/depth_registered/image +/camera/depth/disparity +/camera/depth_registered/disparity ### Intel® RealSense™ R200 Nodelet @@ -216,9 +215,14 @@ Sample test files are available in test directory Both of these methods first starts "RealsenseNodelet" for Intel® RealSense™ R200 (DS4) camera and then executes all the unit tests. +###Developer API: +Refer to the function definitions in [realsense_camera_nodelet.h](/src/realsense_camera_nodelet.h) + + ###Limitations: Currently, the ROS camera nodelet only supports the following formats: * Color stream: RGB8 * Depth stream: Y16 * Infrared stream: Y8 + From 223d6adaf0f29f8818dd61d8e840578b38a26df8 Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Tue, 23 Feb 2016 22:20:19 -0800 Subject: [PATCH 023/124] Updated the correct API link in README. --- camera/README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/camera/README.md b/camera/README.md index cd369e848c..e834cfe1ed 100644 --- a/camera/README.md +++ b/camera/README.md @@ -216,7 +216,7 @@ Sample test files are available in test directory Both of these methods first starts "RealsenseNodelet" for Intel® RealSense™ R200 (DS4) camera and then executes all the unit tests. ###Developer API: -Refer to the function definitions in [realsense_camera_nodelet.h](/src/realsense_camera_nodelet.h) +Refer to the function definitions in [realsense_camera_nodelet.h](src/realsense_camera_nodelet.h) ###Limitations: From 5c57fcc5100c45ac4f85437ec75ff676c413b5cb Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Wed, 24 Feb 2016 13:50:49 -0800 Subject: [PATCH 024/124] Removed kinect frames launch file from rgbd launch. --- camera/launch/realsense_r200_rgbd.launch | 10 +--------- 1 file changed, 1 insertion(+), 9 deletions(-) diff --git a/camera/launch/realsense_r200_rgbd.launch b/camera/launch/realsense_r200_rgbd.launch index 32a5c736c0..f0b45fc499 100644 --- a/camera/launch/realsense_r200_rgbd.launch +++ b/camera/launch/realsense_r200_rgbd.launch @@ -18,10 +18,8 @@ + tree. Useful if you are playing back recorded raw data from a bag. --> - @@ -87,10 +85,4 @@ - - - - - From fb438e5595c52cdc3c126430fc27610e40145e9e Mon Sep 17 00:00:00 2001 From: Matthew Hansen Date: Thu, 18 Feb 2016 16:37:25 -0800 Subject: [PATCH 025/124] Add publishTransform thread to camera nodelet --- camera/src/realsense_camera_nodelet.cpp | 92 +++++++++++++++++++------ camera/src/realsense_camera_nodelet.h | 8 ++- 2 files changed, 78 insertions(+), 22 deletions(-) diff --git a/camera/src/realsense_camera_nodelet.cpp b/camera/src/realsense_camera_nodelet.cpp index 69525963a8..9edfa5b487 100644 --- a/camera/src/realsense_camera_nodelet.cpp +++ b/camera/src/realsense_camera_nodelet.cpp @@ -13,6 +13,8 @@ using namespace std; // Nodelet dependencies. #include +#include + PLUGINLIB_EXPORT_CLASS (realsense_camera::RealsenseNodelet, nodelet::Nodelet) namespace realsense_camera { @@ -23,6 +25,7 @@ namespace realsense_camera RealsenseNodelet::~RealsenseNodelet () { device_thread_->join (); + transform_thread_->join(); // Stop device. if (is_device_started_ == true) @@ -57,8 +60,8 @@ namespace realsense_camera camera_configuration_ = getMyArgv (); - frame_id_[RS_STREAM_DEPTH] = DEPTH_DEF_FRAME; - frame_id_[RS_STREAM_COLOR] = COLOR_DEF_FRAME; + frame_id_[RS_STREAM_DEPTH] = DEPTH_OPTICAL_DEF_FRAME; + frame_id_[RS_STREAM_COLOR] = COLOR_OPTICAL_DEF_FRAME; frame_id_[RS_STREAM_INFRARED] = IR1_DEF_FRAME; frame_id_[RS_STREAM_INFRARED2] = IR2_DEF_FRAME; @@ -96,10 +99,23 @@ namespace realsense_camera get_options_service_ = nh.advertiseService (SETTINGS_SERVICE, &RealsenseNodelet::getCameraSettings, this); - // Start working thread. - device_thread_ = - boost::shared_ptr < boost::thread > (new boost::thread (boost::bind (&RealsenseNodelet::devicePoll, this))); - } + bool connected = false; + + connected = connectToCamera (); + + if (connected == true) + { + // Start working thread. + device_thread_ = + boost::shared_ptr < boost::thread > (new boost::thread (boost::bind (&RealsenseNodelet::devicePoll, this))); + transform_thread_ = + boost::shared_ptr < boost::thread > (new boost::thread (boost::bind (&RealsenseNodelet::publishTransforms, this))); + } + else + { + ros::shutdown (); + } +} /* *Private Methods. @@ -123,20 +139,9 @@ namespace realsense_camera */ void RealsenseNodelet::devicePoll () { - bool connected = false; - - connected = connectToCamera (); - - if (connected == true) + while (ros::ok ()) { - while (ros::ok ()) - { - publishStreams (); - } - } - else - { - ros::shutdown (); + publishStreams (); } } @@ -675,4 +680,51 @@ namespace realsense_camera pointcloud_publisher_.publish (msg_pointcloud); } } -} + /* + * Publish camera transforms + */ + void RealsenseNodelet::publishTransforms() + { + // publish transforms for the cameras + ROS_INFO_STREAM("RealSense Camera - Publishing camera transforms"); + tf::Transform tr; + tf::Quaternion q; + tf::TransformBroadcaster tf_broadcaster; + rs_extrinsics z_extrinsic; + + // extrinsics are offsets between the cameras + rs_get_device_extrinsics (rs_device_, RS_STREAM_DEPTH, RS_STREAM_COLOR, &z_extrinsic, &rs_error_); check_error (); + + ros::Duration sleeper(0.1); // 100ms + + while (ros::ok()) + { + // time stamp is future dated to be valid for given duration + ros::Time time_stamp = ros::Time::now() + sleeper; + + // transform base frame to depth frame + tr.setOrigin(tf::Vector3(z_extrinsic.translation[0], z_extrinsic.translation[1], z_extrinsic.translation[2])); + tr.setRotation(tf::Quaternion(0, 0, 0, 1)); + tf_broadcaster.sendTransform(tf::StampedTransform(tr, time_stamp, BASE_DEF_FRAME, DEPTH_DEF_FRAME)); + + // transform depth frame to depth optical frame + tr.setOrigin(tf::Vector3(0,0,0)); + q.setEuler( M_PI/2, 0.0, -M_PI/2 ); + tr.setRotation( q ); + tf_broadcaster.sendTransform(tf::StampedTransform(tr, time_stamp, DEPTH_DEF_FRAME, frame_id_[RS_STREAM_DEPTH])); + + // transform base frame to color frame (these are the same) + tr.setOrigin(tf::Vector3(0,0,0)); + tr.setRotation(tf::Quaternion(0, 0, 0, 1)); + tf_broadcaster.sendTransform(tf::StampedTransform(tr, time_stamp, BASE_DEF_FRAME, COLOR_DEF_FRAME)); + + // transform color frame to color optical frame + tr.setOrigin(tf::Vector3(0,0,0)); + q.setEuler( M_PI/2, 0.0, -M_PI/2 ); + tr.setRotation( q ); + tf_broadcaster.sendTransform(tf::StampedTransform(tr, time_stamp, COLOR_DEF_FRAME, frame_id_[RS_STREAM_COLOR])); + + sleeper.sleep(); // need sleep or transform won't publish correctly + } + } +} // end namespace diff --git a/camera/src/realsense_camera_nodelet.h b/camera/src/realsense_camera_nodelet.h index 3ccca2b7b6..11f0a56b76 100644 --- a/camera/src/realsense_camera_nodelet.h +++ b/camera/src/realsense_camera_nodelet.h @@ -67,8 +67,10 @@ class RealsenseNodelet: public nodelet::Nodelet const rs_format IR1_FORMAT = RS_FORMAT_Y8; const rs_format IR2_FORMAT = RS_FORMAT_Y8; const char *BASE_DEF_FRAME = "realsense_frame"; - const char *DEPTH_DEF_FRAME = "camera_depth_optical_frame"; - const char *COLOR_DEF_FRAME = "camera_color_optical_frame"; + const char *DEPTH_DEF_FRAME = "camera_depth_frame"; + const char *COLOR_DEF_FRAME = "camera_color_frame"; + const char *DEPTH_OPTICAL_DEF_FRAME = "camera_depth_optical_frame"; + const char *COLOR_OPTICAL_DEF_FRAME = "camera_color_optical_frame"; const char *IR1_DEF_FRAME = "camera_infrared_optical_frame"; const char *IR2_DEF_FRAME = "camera_infrared2_optical_frame"; const char *DEPTH_TOPIC = "camera/depth/image_raw"; @@ -83,6 +85,7 @@ class RealsenseNodelet: public nodelet::Nodelet private: // Member Variables. boost::shared_ptr device_thread_; + boost::shared_ptr transform_thread_; rs_error *rs_error_ = 0; rs_context *rs_context_; @@ -132,6 +135,7 @@ class RealsenseNodelet: public nodelet::Nodelet void prepareStreamData(rs_stream rs_strm); void publishStreams(); void publishPointCloud(cv::Mat & image_rgb); + void publishTransforms(); void devicePoll(); void allocateResources(); bool connectToCamera(); From ade1f25c8b9e39120ffb52207bb1522e2cf3957a Mon Sep 17 00:00:00 2001 From: Matthew Hansen Date: Tue, 23 Feb 2016 08:43:24 -0800 Subject: [PATCH 026/124] Add tests for publishTransform --- camera/test/realsense_camera_test_node.cpp | 12 ++++++++++++ camera/test/realsense_camera_test_node.h | 7 +++++++ 2 files changed, 19 insertions(+) diff --git a/camera/test/realsense_camera_test_node.cpp b/camera/test/realsense_camera_test_node.cpp index b37b12e524..4b1387760a 100644 --- a/camera/test/realsense_camera_test_node.cpp +++ b/camera/test/realsense_camera_test_node.cpp @@ -376,6 +376,18 @@ TEST (RealsenseTests, testCameraSettings) } } +TEST (RealsenseTests, testTransforms) +{ + // make sure all transforms are being broadcast as expected + tf::TransformListener tf_listener; + ros::Duration(1).sleep(); // must listen for ~1 sec or tf won't be found + + EXPECT_TRUE(tf_listener.canTransform (BASE_DEF_FRAME, DEPTH_DEF_FRAME, ros::Time::now())); + EXPECT_TRUE(tf_listener.canTransform (DEPTH_DEF_FRAME, DEPTH_OPTICAL_DEF_FRAME, ros::Time::now())); + EXPECT_TRUE(tf_listener.canTransform (BASE_DEF_FRAME, COLOR_DEF_FRAME, ros::Time::now())); + EXPECT_TRUE(tf_listener.canTransform (COLOR_DEF_FRAME,COLOR_OPTICAL_DEF_FRAME, ros::Time::now())); +} + void fillConfigMap(int argc, char **argv) { std::vector < std::string > args; diff --git a/camera/test/realsense_camera_test_node.h b/camera/test/realsense_camera_test_node.h index 607013f7ec..8679479b43 100644 --- a/camera/test/realsense_camera_test_node.h +++ b/camera/test/realsense_camera_test_node.h @@ -28,6 +28,7 @@ #include "std_msgs/Float32MultiArray.h" #include #include +#include const char *DEPTH_TOPIC = "camera/depth/image_raw"; const char *COLOR_TOPIC = "camera/color/image_raw"; @@ -38,6 +39,12 @@ const char *SETTINGS_SERVICE = "camera/get_settings"; const char *R200 = "R200"; const int R200_DEPTH_MAX = 10000; +const char *BASE_DEF_FRAME = "realsense_frame"; +const char *DEPTH_DEF_FRAME = "camera_depth_frame"; +const char *COLOR_DEF_FRAME = "camera_color_frame"; +const char *DEPTH_OPTICAL_DEF_FRAME = "camera_depth_optical_frame"; +const char *COLOR_OPTICAL_DEF_FRAME = "camera_color_optical_frame"; + //utest commandline args int color_height_exp = 0; int color_width_exp = 0; From c18ba89920041b65e44fa9785f38631a0dfc41fd Mon Sep 17 00:00:00 2001 From: kevincwells Date: Thu, 18 Feb 2016 19:07:19 -0800 Subject: [PATCH 027/124] Updated licenses to BSD 3-clause text. Replaced the stand-in project license file and license header text atop all .cpp and .h files with the BSD 3-clause license text under which we intend to release. --- camera/licenses/ReadMe.txt | 20 +++++++++------- camera/src/realsense_camera_nodelet.cpp | 32 +++++++++++++++++++++---- camera/src/realsense_camera_nodelet.h | 32 +++++++++++++++++++++---- 3 files changed, 66 insertions(+), 18 deletions(-) diff --git a/camera/licenses/ReadMe.txt b/camera/licenses/ReadMe.txt index eb71cd0e5d..ec997c2e5f 100644 --- a/camera/licenses/ReadMe.txt +++ b/camera/licenses/ReadMe.txt @@ -1,8 +1,12 @@ -Copyright (c) 2016, Intel Corporation. - -This RealSense-ROS ("Software") is furnished under license and may only be used or copied in accordance with the terms of that license. -No license, express or implied, by estoppel or otherwise, to any intellectual property rights is granted by this document. -The Software is subject to change without notice, and should not be construed as a commitment by Intel Corporation to market, license, sell or support any product or technology. -Unless otherwise provided for in the license under which this Software is provided, the Software is provided AS IS, with no warranties of any kind, express or implied. -Except as expressly permitted by the Software license, neither Intel Corporation nor its suppliers assumes any responsibility or liability for any errors or inaccuracies that may appear herein. -Except as expressly permitted by the Software license, no part of the Software may be reproduced, stored in a retrieval system, transmitted in any form, or distributed by any means without the express written consent of Intel Corporation. \ No newline at end of file +Copyright (c) 2016, Intel Corporation +All rights reserved. + +Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. + +2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. + +3. Neither the name of the copyright holder nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. diff --git a/camera/src/realsense_camera_nodelet.cpp b/camera/src/realsense_camera_nodelet.cpp index 9edfa5b487..b38939c03a 100644 --- a/camera/src/realsense_camera_nodelet.cpp +++ b/camera/src/realsense_camera_nodelet.cpp @@ -1,9 +1,31 @@ /****************************************************************************** - INTEL CORPORATION PROPRIETARY INFORMATION - This software is supplied under the terms of a license agreement or nondisclosure - agreement with Intel Corporation and may not be copied or disclosed except in - accordance with the terms of that agreement - Copyright(c) 2011-2016 Intel Corporation. All Rights Reserved. + Copyright (c) 2016, Intel Corporation + All rights reserved. + + Redistribution and use in source and binary forms, with or without + modification, are permitted provided that the following conditions are met: + + 1. Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + + 2. Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + + 3. Neither the name of the copyright holder nor the names of its contributors + may be used to endorse or promote products derived from this software without + specific prior written permission. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *******************************************************************************/ #include "realsense_camera_nodelet.h" diff --git a/camera/src/realsense_camera_nodelet.h b/camera/src/realsense_camera_nodelet.h index 11f0a56b76..42a60cc69a 100644 --- a/camera/src/realsense_camera_nodelet.h +++ b/camera/src/realsense_camera_nodelet.h @@ -1,9 +1,31 @@ /****************************************************************************** - INTEL CORPORATION PROPRIETARY INFORMATION - This software is supplied under the terms of a license agreement or nondisclosure - agreement with Intel Corporation and may not be copied or disclosed except in - accordance with the terms of that agreement - Copyright(c) 2011-2016 Intel Corporation. All Rights Reserved. + Copyright (c) 2016, Intel Corporation + All rights reserved. + + Redistribution and use in source and binary forms, with or without + modification, are permitted provided that the following conditions are met: + + 1. Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + + 2. Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + + 3. Neither the name of the copyright holder nor the names of its contributors + may be used to endorse or promote products derived from this software without + specific prior written permission. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *******************************************************************************/ #pragma once From 817f09f49c50de40c734649f282fe62635dbb226 Mon Sep 17 00:00:00 2001 From: kevincwells Date: Mon, 22 Feb 2016 19:01:37 -0800 Subject: [PATCH 028/124] Add ROS Navigation files and documentation for Turtlebot. Incorporated the robot description, launch, RViz, and documentaiton files from the old DS4 realsense repository into our current project. Updated all of the files to include our current package names and launch file names and locations. --- ros-realsense-nav/turtlebot/README.md | 122 ++ .../turtlebot/doc/img/bag_screen.png | Bin 0 -> 109838 bytes .../turtlebot/doc/img/mapping_screen.png | Bin 0 -> 260595 bytes .../turtlebot/doc/img/screen-ds4-nav.png | Bin 0 -> 151742 bytes ros-realsense-nav/turtlebot/doc/style-doc.css | 46 + .../turtlebot/install_realsense_navigation.sh | 10 + .../turtlebot/launch/amcl.launch | 78 + .../turtlebot/launch/gmapping.launch | 59 + .../turtlebot/launch/navigation_demo.launch | 40 + .../launch/realsense_robot_description.launch | 14 + .../turtlebot/launch/simulate_mapping.launch | 55 + ros-realsense-nav/turtlebot/package.xml | 22 + .../custom_costmap_params.yaml | 24 + .../kobuki_minimal_r200.urdf.xacro | 14 + .../robot_description/meshes/sensors/r200.dae | 890 ++++++++++++ .../meshes/sensors/r200_entire.dae | 1256 +++++++++++++++++ .../meshes/sensors/r200_entire/texture0.jpg | Bin 0 -> 2508 bytes .../meshes/sensors/r200_only.dae | 890 ++++++++++++ .../robot_description/r200.launch.xml | 35 + .../turtlebot_library_extended.urdf.xacro | 22 + .../urdf/sensors/r200.urdf.xacro | 96 ++ .../urdf/stacks/minimal.urdf.xacro | 84 ++ .../turtlebot/rviz/navigation_r200.rviz | 379 +++++ .../rviz/navigation_r200_without_depth.rviz | 540 +++++++ 24 files changed, 4676 insertions(+) create mode 100644 ros-realsense-nav/turtlebot/README.md create mode 100644 ros-realsense-nav/turtlebot/doc/img/bag_screen.png create mode 100644 ros-realsense-nav/turtlebot/doc/img/mapping_screen.png create mode 100644 ros-realsense-nav/turtlebot/doc/img/screen-ds4-nav.png create mode 100644 ros-realsense-nav/turtlebot/doc/style-doc.css create mode 100644 ros-realsense-nav/turtlebot/install_realsense_navigation.sh create mode 100644 ros-realsense-nav/turtlebot/launch/amcl.launch create mode 100644 ros-realsense-nav/turtlebot/launch/gmapping.launch create mode 100644 ros-realsense-nav/turtlebot/launch/navigation_demo.launch create mode 100644 ros-realsense-nav/turtlebot/launch/realsense_robot_description.launch create mode 100644 ros-realsense-nav/turtlebot/launch/simulate_mapping.launch create mode 100644 ros-realsense-nav/turtlebot/package.xml create mode 100644 ros-realsense-nav/turtlebot/robot_description/custom_costmap_params.yaml create mode 100644 ros-realsense-nav/turtlebot/robot_description/kobuki_minimal_r200.urdf.xacro create mode 100644 ros-realsense-nav/turtlebot/robot_description/meshes/sensors/r200.dae create mode 100644 ros-realsense-nav/turtlebot/robot_description/meshes/sensors/r200_entire.dae create mode 100644 ros-realsense-nav/turtlebot/robot_description/meshes/sensors/r200_entire/texture0.jpg create mode 100644 ros-realsense-nav/turtlebot/robot_description/meshes/sensors/r200_only.dae create mode 100644 ros-realsense-nav/turtlebot/robot_description/r200.launch.xml create mode 100644 ros-realsense-nav/turtlebot/robot_description/turtlebot_library_extended.urdf.xacro create mode 100644 ros-realsense-nav/turtlebot/robot_description/urdf/sensors/r200.urdf.xacro create mode 100644 ros-realsense-nav/turtlebot/robot_description/urdf/stacks/minimal.urdf.xacro create mode 100644 ros-realsense-nav/turtlebot/rviz/navigation_r200.rviz create mode 100644 ros-realsense-nav/turtlebot/rviz/navigation_r200_without_depth.rviz diff --git a/ros-realsense-nav/turtlebot/README.md b/ros-realsense-nav/turtlebot/README.md new file mode 100644 index 0000000000..0c34102b54 --- /dev/null +++ b/ros-realsense-nav/turtlebot/README.md @@ -0,0 +1,122 @@ + + +# Navigation with Intel® RealSense™ **R200** camera +This document presents the transition from a **Kinect** to the **R200** for the ROS Navigation stack. +It assumes the **R200** drivers were already installed, and that the navigation using the Kinect is working. + +#### Document outline +Click on the following links to navigate this document + +- [Initial setup](#a-initial-setup) +- [Mapping](#b-mapping) +- [Navigation](#c-navigation) +- [Simulating a mapping](#d-simulating-a-mapping) + +## A - Initial setup + +First, make sure you have the latest versions of the ROS navigation stack. Specifically, check that the following packages are up-to-date: + +- **turtlebot_description** +- **turtlebot_bringup** + +Before being able to use the navigation stack with the **R200**, you need to set a few things up. + +The `install_realsense_navigation.sh` script (located in the `install_resources` folder) will do everything needed. It will place the required files in their respective locations. + +From now on, if you want to use the **R200** as your turtlebot 3d sensor, you need to change environment variables: + +```bash +export TURTLEBOT_3D_SENSOR=r200 +export TURTLEBOT_STACKS=minimal +``` + +To have quick shortcuts, consider pasting this code snippet in your `~/.bash_aliases` file: + +```bash +alias setr200='export TURTLEBOT_3D_SENSOR=r200 && export TURTLEBOT_STACKS=minimal' +alias setkinect='export TURTLEBOT_3D_SENSOR=kinect && export TURTLEBOT_STACKS=hexagons' +``` + +## B - Mapping + +The only difference from the kinect version of the navigation stack is that you need to start the camera driver before the navigation: `roslaunch realsense_camera realsense_r200_nodelet_standalone_preset.launch`. + +So, the normal flow would be : + +```bash +roslaunch turtlebot_bringup minimal.launch +roslaunch realsense_camera realsense_r200_nodelet_standalone_preset.launch +roslaunch realsense_navigation gmapping.launch +roslaunch turtlebot_rviz_launchers view_navigation.launch +``` + +You may also want to teleoperate the robot, for instance with the keyboard. + +![](doc/img/mapping_screen.png) + +Once you're done mapping, you can save the map with the following command: + +```bash +rosrun map_server map_saver -f +``` + +> Don't put an extension to your map name, the .*yaml* and .*pgm* files will be created accordingly in you `~/.ros` folder. If you want, you can also provide an absolute path. + + +## C - Navigation + +Once you have a map, you can start the navigation with the following commands + +```bash +roslaunch turtlebot_bringup minimal.launch +roslaunch realsense_camera realsense_r200_nodelet_standalone_preset.launch +roslaunch realsense_navigation navigation_demo.launch map:= +``` + +## D - Simulating a mapping +Now that you know how to map a room using the **R200**, you might need to repeat the process several times, to adjust all the parameters of the algorithm, or to test with depth enhancement. To avoid using the robot, we can simulate the scanning process (= robot moves + camera) thanks to **rosbag**. + +### 1. Recording a scan +The first thing to do is to record the scanning process. We will store in a *bag file* the required contents so we can later launch gmapping **on the same input data**. + +So we first need to start the turtlebot (+ the teleop of your choice) and the camera: + +```bash +roslaunch turtlebot_bringup minimal.launch +roslaunch realsense_camera realsense_r200_nodelet_standalone_preset.launch +``` + +Then, we will store the relevent topics in a bag file: + +* _/camera/depth/image_raw_ +* _/camera/depth/camera_info_ +* _/scan_ +* _/tf_ + +![](doc/img/bag_screen.png) +*You can visualize the bagfile with __rqt_bag__* + +> Note that we don't need to actually build the map, so calling gmapping is not necessary. But you can do it, to have an idea if you're not moving the robot too fast, for instance. + +```bash +rosbag record -O /camera/depth/image_raw /camera/depth/camera_info /mobile_base/commands/velocity /tf +``` + +You can now begin to move/teleop your robot around the room. Once you're done, kill first the rosbag record process, then the other nodes. + +### 2. Playing it back +From now on, you'll be able to simulate this mapping again. To do so, you should simply type this line in a terminal (without any other running node): + +```bash +roslaunch realsense_navigation simulate_mapping.launch bag_file:= +``` + +> The path to the bagfile is relative to the user `~` folder. To change this, use the *home* argument as follows: +> +> ```bash +> roslaunch realsense simulate_mapping.launch home:=/tmp bag_file:= +> ``` + +When the RVIZ window is up, you can press `SPACE` in your terminal to start the playback. + +Consider taking a look at the launchfile to see the different arguments. diff --git a/ros-realsense-nav/turtlebot/doc/img/bag_screen.png b/ros-realsense-nav/turtlebot/doc/img/bag_screen.png new file mode 100644 index 0000000000000000000000000000000000000000..ba66d73e7ee403b74dd70989e97afcbbc506b771 GIT binary patch literal 109838 zcmZ6y2Ut_f_CBnlA|jw5pdg?KB3-Ep0@9`T8XzLl2}rL2l}>~xNRi%q=mZ2wl&T;l zB(#K%v_R+tNC^Bn=iYPf@B5x-=SlYLJv)15*1WUccdd!l*Hx#x%69eKxpQCK*HXG;dy5c%M5*-}%?)e6k=t`&r>_A60W7BM%23e_Jp6bB^vFAbVkNJ1={C zcW);TpG_*H{JC?do*F8O#sN0#S=4WNR7ZMdmfk#F{>gD??&s6{b1{kDjK&vLjj!J{ zR=GX|b-JK>@s~zjqW2T8W-5{Iirm;x50%qW<>L%f$=!m>$d*;*eM!#%l(w~5m-^k15*04$E%(A3SnG6k z`9+=gZ0!2qQw?@k!cNYr-tlj)-g0+y$-~m^OW4=jHXMxSNg(_sO_EuSj9mHpD?o)! ztU@KJ%T>8H;2?cplOl94$2j&SF8z_MIGeb`wS59Qy0=%W4Az+CBITAFNy{=c`E|F{ zKMK@E1Bolk`fM<+ZD}#}`fu@)w|Tzl{RMMx+g^bs<%gj#_Lp z1)nS7ruhT9C79yow7A}0XLn^;>)iqEa#4Z&Y`Kc8_Koi;_Q^w`WP;t;sv-ykf|td^ z<3Ip=dwXLbP|pK#B*o0?>(FT`vsx2Z3TulG`h3$s-7_|6jZVcMti`;~`Rrpi6t6`9 z>K5^G6k!b7=Vgr|CyQnGw*|Z8ph)~9T#^K z4P9!w=2WW(i;H)>$}5HZuQGl&1w^Yx-|_k={86^FprC_);&WmmBj8Eu5JVKAv}oVu z+?cGJE?e%@f!)V=jGtq})WzW;f>e=KttL9IWBd7#&E_;eAy`pr_3@=PQzLB{vs@P2 zL{Gk$Ws?J)q*RlB$usY`xURjEcWqi_`Q_9WX`4CWJiA$s|LM`g?ZYJamOODqS^CCw z7ChgwK1hxN%ISCVvB(f^Y3l;9!VhhROqE#MWOFWGTXChGjyQY|8*v>)D^i0Yy&wbn z+B+97dTVLXwvq7c5|4D?!x~!Zk|R!BU+-Nt7%IzGZ_% z_)E`GTy$y!h-qs{TvOYwK^)#i(vPZqfs$8I!a-%WT8HHu8-Hds!B_9i@P6` zS5)sd?&B+}QQrc0t{pelWb2wF7>3J$EFf@hHq9yY1}&eH8;3F=R7=rIT$ zs+ng=KOkxC?c}pyUml=QC^flW!e$3cLyC#^+IlU}fpAHeN^880*y$D-bp{u87Pq z&`R}~PJ*vms{u#hsD0oV+61tl7dz6GPtTk>Wt&ND541(|r$WP*|zg%T`bVD4qU zcb#%L=Al3GJsYE$p%#IIal-GeE2qZ9NE%5Bg~|I} z65A2GtI_0yqVuoTGn_{%4_3EZPnBuegj|HylqK0^oGLnWbCc+&-$|{xve$R5M32wF8dM2YwY5**L$8rNE16%PAcxD~@czhcU3gzgr*-}gws^TrNvE^~DrNxbjQVI)RB!Y7=&qXT$#M)9#jyfS9 znAnq=;pk!i!F#WNJb>OHmNPz6%wGCFMzPjC!X`2u}plr zfBm@m`T4IUrXCNmk#DuNk-F?|W=_uQ>89=z?Jd0?mLG)1_km`md#SpbWp^L>X2^{K?keOOSTXk9xNarkdHM5yio4+ z^YbavGpj72b`Z+z^W*Rc6Db-royZ69t5fLwTIc6C;B4&MAG{pRE|LJ$p?%`NWJ+g- zhVD4g{sjHq7tKND&^HTCBes|Ie~h&=Hc9F>e;oqGMsbrdEjUv*w}H|L?>G*nC=YeewC=;3%Ek}#kT){4K!mU zwZqN{h9T>xr{P`E9~_|T78+&*`E0n8xhA241u|IS$EDs8oZ>&CNNFPY*)JANxxuVz zm9!7sJ$mXV9BB4YB0pIU*XswRHNFp~XkahORup!!c)Bj5T-MF>^1%;G48a5!0shSs zgkweHC$@-_O}&L^v*CH){swq)q=3xhr0;DCg&RJ@aV=8m0YBeKTyE{BbslAd1VL|U zo3njjX;Xw!Hid(BVS~>6*|C03zmZ zn{TISa@N^6Og%g0;YK;~yb=pbv?~!t1FM=dN9b$i8&l|wFuN(8pWpqv{{g1I5z2<< zCWp-8IkQGXAV6=7!L=C03nNy+;^MSQoAcvjGVob4ex@c2csFPGNGi-UF3wp|{i$_r zetHmbU6CEQ;AQ{^jXu(b} zExr4(PuY$xVc8UJWarFPULjhd9J(7!8n}2vxoC7r>TK>a;TlNDz1cT%O2bT{ zDNaUOA>)KtAxD!`zn0oxQWS3@;n1#M-cYo-kV=U?`T!lH-WC76leCzFl+P{GX zwrP-6+V>C3V0ym{42aj1!nv(KfK)hZatT$LO^=@kuGd-4!0t20MVcp$o+X?PX zH(v|Jq!1AeW@ECAz&sDUZ0Qu-z}Ql$eun&BCMv$bvmxZ$8Bl(iynBlso=vB%=iIJTre}5K9 zq~D{unA1KBQxo)9*bT4OLHew}9CxrX;h$opp(+Ncm^ktMJT&yHb%mJ_DpUVKrkyJ)>GC{D}HMs0f=cAOI68Nf@aptD4Hs-?`!Q=d9c6r3H%{ z2Z1`s5TAP^O^K}x=9i}Br{`Zau~WgrJ*kPH@onkSE!H1^m zzkTw9xfE^l3S+7<`TGR;>_%xWLwfIO+o+2`{iR3QKZsOtOG{j-Ba{knMO&Kw+W#zdn%a`94c9iFL!xep|HwTJ-iHKMJ zO7TaZh6>Alt%Tc3FDIw~Q1TcC_g{T}=+LB5iZ8^t)L7(h`Y? z8m+R{VwZBe&VAd!Ri#E8BxqtO+gs|hmB2njLm3uwVMYIHMcbO_1Jo5{j(<}*x%o<( zcq9fHP^bq{d=lw6lXwDl(a_}UsP`={BL z2;phZ^%2g97k@P;B*fpM?K%Na=snm1`Y^@5XGxqT`4&9(pX(|9eW(Wt*@C zYXPhW@c&avKOKN(nQmlvF%J;`_hxOjm62A4qEl0yHsMJzE63NV=WOCNhJU&^gsMh$0;2OQ5WkxnSu{^<|Dn>Ajls za-UkY0>-L>ph0w#k){L3m+0<%dp9cNQILn5zRx{H%PLw(Xqrl35w_7@EV7pfIeb&{ z^nZimR#;GwwG<+kfyH9oY~|jUR|H>Yej3RLDa}J9m{wWoj>rWKH*Yg#zK>Wz9HVX< z&L(@e zlo#cs3KEJ%owv3eEZa(>qTEjJg16>^jSUPmI@CYpRwIrR>Bmn2x<>33De}jC9xEPP zl|?E;Ii-a`*W;&L{AG^+*f|}{F=u=b{rA6UyQyweysl;!eA7rhn7u#!X}DSfn{xPN29`$mlNmRXmj)G~e*YoKA&`oW0MOxE zm;VrCnrtX43p1Zlg6djpR!B*pB5dVW`bAlWt1|YBxH#(!zBzsv2uj~wO4{qx+C-Z{ zq{dsCKak?5Qi$^F0Wv|=C}YBvSKFMM^TV2KLt$(qu#jH&aW!6E6U_94kO0Q5v`8LI z9zKrTE&D3@X)JO?cfZ07CAV|2WxaQ1C^;3Vr0~qy48Pr9zn3~Qr2~}k>3{hzSlV8F z8%eu_{(eunY&<2eu~CJJ{z*<~;F0KRT@DzUFa^E~3s}tY84*3z^r%`d+=^sG~pRS+=hC zsY*6*J?q6h^Dz+x;7K?rv^3eYwIsMB+Jzqf@Fq3Q0>+E^AIrO&QK# z+GeoRA`yqZbUMZs4t+tbl~rF&R1oTPcx63=0&x82wJhV^xhbDzvW~=2>lk`OLFOGj z*4qpV%Hj9H4ptRaK-pCVfhV$Z&+2c~<1cmb+ABMCu;p*#bo1&%{ls+S+o;=GTE3iY zbx!OJv>;K*&^sC)18op|YMT}T7JJ^a%cUSH8Hie|{+%~~0H8*xv{e0medk!g&5)l` zi2i01^Q3d-C-Vw>CDDinHx!!Eod*iWhJ2yFi%+Pt)KhIvv|9eGXO(&XkVyY3a&PkX zKhTyoc}@|~SN9XYt{pQl;I}>5G-A6sQC2$kT4rP1Qw3sEB+c3w6XZlCpV^jKE+C*H z(K_Xhc31}PulNLQB=KTgHW^l|)nwy0^`MBR7oYP6F1Nb-+CSCFYSbS8c_oW|WtUaH zB;_47x{Q1+PmB+sZ>+JvAos-&R#|jla~zePxjuiCBc~THOg5|qztv(DF5ulwMeq2s zNSg2a)ylmj<}x2xYUf~diUM=Kr8yOe?V6G}xknr`m1mHLK|w1Jn}*Y;e8VXN5yZr4 zCg9qB*2X5c$0S zgApws8V{aeVBA)MF5n@qtb=7nPTfO|;>6JpKx=2kZP@^f)OmSTjmI$D5t8{>7y+c@ zv#={mh8Be(AE%xi{CZ^&CDRz+pWlz)XOD>gFoYN-W|g{OOeG34@VffOl5z0cnwYwf z$DkK?*qHq#q{pchF_@Y-wlx-1X+ppAb3#>v_x`Al@gNO1Vf0C6kPopgxy`z%RtjY( zM)V;O_Qz2BW7f)Ml=%xXfd{XGc2j1Cki{d4aHHLP>6NNAkuyGdAS6Sm91c!tZf!b1N?H0L=kaS$R#lu zFxjQ#9)clwwk%C^fr6F%$C__-pNm=71qAr}(RlO?tQGnJUf%b`z6$L4_S9IJ;-r1b zs2;!<;huvRvor(frNCrW8vs|fI_syy$)>|4yJHV_vK~Hx8~9H}1>wiU!}BJGPbA#$ z8sHKw8Z;5}T0dNDG=VT40WPsP(r2EXxV5$P(z2p2c&W-fy0sL(VJtH{x`o+q!qNrg zoJVR=du;NZp`tC8ZGAwiS1VTPcgfR6dx@iFJEt624{ko>SvCAtp=Y|1-79Klr9XYg=i zV`Kce>nK=Ot(D|eNSD;k>!vUkEd4SSF~1R>{gekH%h2mhfh(c4#u_QK*PyY zxWa3(WLRh{XQ)53F9ZtcZUFGxY6f z*9m1g{z8A!L!Csd8fiG3Q$S6LhAD|VglKvkALv-(KmX6I`>GtMddb)FI*w*)y!jP< zf9BJ0#Nn}W5Mi}-wWZ=jgUb>(w z2JON3!j&Jyg7^^zCFm+Zy%&F0&7f(!n#055(BMq18C=o(V#@B-7W}3jYK<#IGw0jE zRk@wzvz7PM;sq6QpGpQ)fv-B6R~c}X@bBLdi-J$uddRE*WQWr@yIxO}?mk*6WnDi}zdP`Q9$9%)2tr6xQ<2>2bgOwXT`&0D|0LZ`C z1c{3){aXKls6ga1o)QGFB{T^KW{QxzTqTbDn})tJ1^oJVmZn+dodt!a1NNEO9=$mi ze@8N|w@)CV5@UL`fJpQs;VVQ-8;g?Z<@et3jk(WED=yFMT?f~HOXwwEtMe7O*m4Ob z{C({Q!)xY5cv#ReaMCCj z6P}f6>|9{K`Ar+h%ur-Y6{PP;c}1Enqh490Bcn}D{iQ%QtH%GvZfw2YM@0ptEBK4_ zXGll0u``P2Ox-&3q_7}pTV`AQ^N^XtS*^YGR&-fG12waWv7x8N{8!gLmUUBrICCQg zjUp4CD=6&ennT?0MjW(yAlyc(tT$dCp&e(hU>#bsGTW}KOg_&!AwOtw#Vc8kVHAxg zlcMydqZ1T%Rj^?5qX+(~|GF}1?JrO2M)tl#Hqn5b!D30t*fC3nbzBB<#*;D2@29(j z-}v26to{*ORa5#49PK6?%%u2@%L(1>_f9z9Cg{n z)uRY*nwt8t=*BZ1;8X#hiE+yyKd{M9SW;3lCV5m`!`b;Z-K|F-gZ5Vme|-3KL+9o_ zQmy?9TCi0nv=^WGP1z#be<)D>>X>nU(jHPGm?B)%Lb5EcuJHB}Q~rm^;6gROg}nZ| zC8!(i!Q1VDEYtl{)idYLbep-Gs?^1hihI7k$gFJ@1GY(} zD7&&I!xWmcO9e$*tPlt+PgxqlAd(Qe${O~}Z=(h{H=FbB&)lZOod+}g(}bt~18y#^ zpr%V(Z)y!)4jeyWIF2Jfk!>INOn}xOf6Tbhb2D29@HOPA$-%m!T@UC%+-PH#7 zUqz`_UL(2pI#l+)GKot1+q{|PpN<{14SU6PL?BAW)(hhUc?7q=IIXQiK&@>xkeyDg zVXZSIQoY*7xD^o{h!tI{)e#j?t};=fHPQMj-TPr@pQ{?u^+z z?@JMa_Y_44WW|Ksp;*>C(8b?+oM_o4I~urd{F+mKqB{O?u}|;hcFd^y_fU|^(j5Aa ztaY19(Rg=-+F4AXtgt~vDBtiEUjzS-83x%{3S%&iAD6~xA8TChRshZyLKT~j3pOSl zHjw#61X$|pNJN4wxfwGcScK=4liL3DH!JR@wL;#s!{6zw3CJ=xxMA@cVn+sAv09i{ zOkEab>mZ|5vfIM79zZg|UuvKcUWF>WCBM7jyz4Q!@5hzS#EV%)V<6HKKUJ zZ}p4uAAVn_)M-f1+q?iFW{_kvR#A(Ufd8aY*y$PoTq{PVM;~0Q9crJy&^P^EO5{TW zt%%j55e#N1^QpJfNVy4Sa#CnVP(Z-xu*Oy*wEZF;-P#o6!pd9#1HZHP&}vmx?V|Z5 z-09ygC6dYVJ4abL(>V$VejM+I^X96h!_Z1n-qYPUDl;mHD~;4NGD?cc{J^D<9YxO} zfIaW5>|T(S&DZpU+GwU2#^=EY?>KC9pOQ(J2e-t;#rR_+<5CC(uLWDSJki z2)EmGT=JQu{WbNG5tICH2*kTH-sikM-zDLKd58^-CeWY{q->g>MiKPNIy}oFtnPhV z1}iH^$JZRhAkt2r5^Bc~`B|a1#iV_dIu|ODS1W?6braE=lu^2S7TFlO7p* zo|sF3YgxU%Fp?eDAl$coG~Mcf`U7fWB^QUzIegFXKxmu=Itx=$SS%Zy?#UhXC;Lp# z@ySXuPHrQkS36-Rcku`K5s1TJwoXZ=S6uTGlkHtCn!$gwq_`)kbKF-ju1}{Q+$>RC|Gc9q)FpZ?9Y27O-)d*fEz>K~+FhnvQKKY9M z-UE}f+Uu!bfh2#@w5$gTF1!B1J|^Hko3*7Tdt}W7kz%WraTFUH@dKbV~I^OC(My-g$*>C`hdEblg2;l}DNbf%=tqiwpenh%qlo1?qzu-(nx6FZ~v<}Rwb z75X2KIP@l8mBSXax%@f}EBj$*(RC3CsWV)kSA{tL{Fv9^#hbmR_Igw{Z{Xv-aOacb zKyGYijq52Ca?4TH^NYPl%ms4TAK4g)sDbDwJ`tZx@M@9}RdchEC~4^AvypB=lAe6B zuFUF9?CD#oQnSr$T@d@kw5~NAQ;3=PbHSu+VbRRUuAup&3I$c5j&5*9tAwhTfIpS< z=%3}e^`!_i?cW>T#3$ijzJ^_*KmSejUI7-$z zVL}{sd;_$Ofa38(do*g|MLewDX%Hq|0B}1$tth@~40wCm!!lc!rClyuTkYo0JL|@` z!1~=kAV==9R;tiy`Ta9b!b1CCYNk!dC{)<0;p0Xl*(PDL`xomzh(*Y12zKqLFGaLq zGwk4*Wu3&F>n-HjoQW9ifQ#@9%AN*KC0a(cINkTjr`+!DF{bQjO>AkMR8a<*pu@gl z&BcQEM6V)^??xFU5V!PrFsuen2k?#{c$`GJ2Or&rEg99E7-ig~Up;U6X$JZ2(`7T? zFqS*>9DXW{;HO}v2w5-<@IMZ$QsR}qxV4ndE|vNDuCL>7b`a^0J6NjPTDd0)9EADz z)HyLy_sarH(fTvb<%0JLzlb|rWw$1-N67zy4^8WSRk1Rj6R*VyU$~!W-Bj_r7?c#_ zf50Ppfwx82^Ig%OcU9oWoHW`L7dMx>QyuN6$lWtO^EDD#VoQlK00etCNi>}52hHw6 zR{Oh7uV1)RUFO_w?A?=61{AREu7U|~v)wr)A8QSwy+!5Kg9%?*&*FDCTP^ZAdTj!Z zE*Zd^tflOG^Q`SxZ^=q_^@|Q+N45Kf~B>{I9P zyh%W;aqj&-&CW{&f-Qssc>5BbwG&;(rdpEE2kL49R*!FA&+%*DynL+d0%{CPohWl0 z%=Q_aI*5$`eSyl93gR@_KjpY4fTu*OKhq&Uz6qr)nBPX^&tB{LR-n_~ABi7`fS|RY@OqT-#$b6H006EsQVi(S5MT zA&YdgT;HTyh{8-_RV3l(fJV~serb;qt7OSNn8|J4EC<@Ho)UMq^VA09$Q<^V>hlyb z&0~O-8*1v{7~;^M&foinsS=1p_+UP%PbihuS5)@VC+hrJun*rXJbioOvu7{^uU|); zf?4~&>^45^&?yUr52{bdFSMPWB9=E)LR~WsKT8cCi4S4Y0xApYnYf4Z6^>^beHQw| z3K7Jw4}M7P=ts%?g}j1iVJttJ(62>qN6A}s(4No3{>WWQRgZI!u^A-9f{z(#9C01q zr=JkxEo<}6`IK-y4EniHEZ;xajLmpTlcS&ADFbC9F+4rvpu%s$ER8np(8|Kn7z31i za1`HM(N;ZFQ`Ri)-;`3@yi`>_3XH@~91 zyfm!(p3gdcDjLESR;STPPS#T>;79XN&U z14(KmZqv>_V71wf_WT|kRoi~rlM~9*dp+LDtUkd-s@99S^#mRbflyElxyxmo>4BSC@OmvZcnd`xD|Xm8P1HJkHb8VWD=#f==s{ap>0`WV zJ@{hrXF1={c%68^Df(7Dm3U$NLjoNo9fg&xn`PQGl_*@pleyP3KZbs9sK#$Dj2-r{i5Apo)Dv)N*YSc&T ziuEi#@;Zity-QLgLF($(2EV})rfbhT7^w2NrC8K2r~68$6#mIii0HjxRRs7351fg= zwi>fpv%4JX(`FJHwof%cY??e3yce`d*OjYh_dX5C)t+|*hKNy*d%`5n5Juw zaxrVn8sFIXYaK6*<|l<;reiUv*oQxHtszJ0ySlf#MS5YwkQ7xOS_p$Jswu_vSw~J9 zAkf=8OarA<4ixkaxyZj-2~+nQ90!rssTZ%@;dBV@A!`l%H7W`N`++ zeu8QSTN_=?ARp(YlA2iTBAV!4e!%0`oc8g_ei`&wmo=F4VlT7L7;^KblyPf0q0_H! z!9I5L;tV^>sHGh_a*W%fb?UXJ(N+0-bKs$h(ecoUQ#yFq2=h*(|1{TOC-oL!%!vQco&SDzI$BvlDDI4ml0JBo~$@h-^@DK>wm^B%Mc z)&4~)N-TvAcEV$naDFHjh;y7?Pt?Uv8#DlDA%~t^I9$$06bsI{$~JM(#y)l zFGBnyKIN{Fa=xLgwDLM`=e??xxh?L5!H8a!wLMw|_}u2W6jT$h_XPvts_36?65Wy^ z(Edn>vc#8Ks}t7DjL0p_7`Xe>Mwo>*OppcZEZ-=UqXpAiHe5*TvW81zwfEi~SDg^R zv1LHRfP)p3atxPBJsbR3d+Bm5Ww=iil`iS(RuP-L@EG*9?CE3jy-H|t zXclbPh)%GWg@?i)p6M)%X$EED^81f^|nB@c(eJ zWd#-632BQEz6d-EHfpQNpV1dI{A~1QzHFI6NnF6!0;*WQFD_j7_RVEGw4Hc+^68-@7v+4@9#&C zhwaHY?UahKP1YOnFz=lQY*C^6TS-g`9kCbx>n64j?|<+=^9EUO$3j@O7nyK=Z1Qdq z&2OV_r4GLFS8Z&J5HskhqJ8|x<Os>lKnpy>4~oM5p8#UKKUdp;XtmjI(-?zR!Lv-I zp=A-bW$(QP-PrpP%{62O?7#m03Zb@6rrWoK!#}@lQ>SPZjl7QXtUQEV5zzmujuA%V z)%u&H`LnzRE!oX)T9wD`U2@;Or@Z0c-2xe^Q~j0xeY<%r{2A<=Yn`wgy&Rx8Q$33{a{87%avCjQyyGlK2sy2jJS5OQJUj52s>P3&kr zI38%1xyIY_E)2y>F~a}@mY-Tt+CqU27x=fexv~WRm*z6>m!(i zg7kZ41|0*Zxmq6JcP{>I1%g?j_%FJ&tz6^p!G}DIq`K4M*ptlKTBiRx7!h0D_7_F` z7Q3K_V~Di+H|O1!LG}Hk#%43KRL}YUjx|8+C+uT zYu=tE%JBETTtMq7FfTd@64FRTb+y?@=;4Fwk?jYe-DQq3s-NUZEB7toK2IeveEA7X z(itBgR+Q%-Op~8~tD{9ny=$<;7nA|TbZ#Ln){igr!{RY6VI?Xi##WOV#llvKO$w*n z`xVn!8z*xTGVWuLbw8)p+N|_5x*;JkiayiHoUjd|PT$`u`Ybs+4j+0hs9IQ4E^nt- z-3Im-zO%MpXu7x z#b`ZQ>r6-hMrrRp;YG&bO>oO!EdTyM*l~8aey2nT&*9sLI~CPPo-^@-ug~CYAu+{1 z-ha%Dd~aAxNz~ZcaUF#4teWy^AdMLj6JhtakPCLN&P%k??GP@gAbG(-rs%Q7=%J4w z-C{cb9JR$TY@C4m%%}2=@h@s}EvzP!wMN`ia5~>-ZyKD!H*ZT3=p%H-b%iRI4j(2( z|Dy@;a8Jjs-DX!wX9N)UBb&d!u!-m zWU7e9(z1CdnQL+7L8B0zss=Tfg?&$V7YsWr;4+B4Cn zZEAX~Y&%k(>~nHSfw}q#yLiyGc$s|Nw%M~WHNoR zE#Ha8@pRXH1#5UAsDukuKdPi9y#(##&NWK zd}T(z?Uk}Z;pQ`T2UBNuP;;;KyXps~-D2*LC%AkC>hTvo(2!+rI*mWFtl>5M0yr`O z4(*4rM@q?e!5J63OUB*vxykiE5ou9$lNa?t{(9`9hi}V(dJ2?l*8WrbuP&`FB*-R+ zw5)KqETy}yh=v`}Qphu>#nfCOA2|bN&$pcIgjvlwJudl)TucG193YV?HbJY4L!o79 zq$?l60SZxjbRdPVW5x#OX|@=sr79VUu{Hp9-9J&v=MS(5>majJ0>7zKmO*zeCQv z^K5*e9u%?tm%}(s+!X(|as54QwY-pbL?J-wHa=Gbn+q~O8}dF;d$i~?wYST=+sE=} zlbjNd@m@(JB&H$j z4S$4cM#8iCH(0m!i;p?j21D$4?Z1|?!51~VnAT;YxkA&-^?$+Bn@4p^-E8%U{MpOO zNFqGwaZLqkr$p)muU{>x`sylOlRx21ea?RqBvl5C-}q$i~5uQMeD2{PEK zGdU3QTUS6tB%h;c=Fs!yL5`_&J)-QPihFCJ6Rqvl zzW{pEoz(?M@HOy^i0o3S9f$1FU)K0!ahBg_hH`*te}X^ zb(71@`tNU_dz}5~8k!i!+huHEqX-0VKh^QcPZ32P-r)$`+m1+1V`5#}$)_#aVKRrC zTdT9XNXLwLcbT-YI=xP{D+eJF;4UAJfVU8V7#TMzZAg!CV4)bU`c$6sgyY%b8v_UY zSi>rMC5qj>w#V6;yW{%gi{|~5j0k<{eb>=Si-x|cR)Z|L%Xfc|=P_*GIwwZgO)vSH z{V+M$%r6uC5;w8h=YZ zGeM4&_IJ3>2&$k-CY%aCCUCW3ZDK>7hF|4en08l+>u3RSo$$7-=7Tq6F^9hwjVXk+ zve(Dca5?g3)|8rYeUqv;S$UEV4t@_hj1jAxrMCeus>*b;?6&-O#kARLUl_YS9b>~+ z^EHr?+ryr#J ziy4u7$6>3bc6zy^DJd$Q=Woy*JBGRQ)C#*Z<|>5bGcXKsF3zK?py~51*Fc2RH;Q~2 z3;WNS?+R9z<~rsaGjMo~f8tj7Zw!Aum9?FVtg!t>J#>5U`N>gHSc%@r@{N1nn55ka z*HBV(_fNF6(O$>Ni$A*&=)ni$psq?Ga$1+pt5(jCh9<@b>qrw_X+H<0fP(5Vo50uv zxw+T>%^yFDlEu4z=!}d7&m}cuYfgViiG1vYCzWvTFlJag1;#?e(>@c|f2(-3SABcf z;b&(=mHcua5Pg<1TLPmyx#7puy%?FX#lVFR^W#j6`<=AdJlg?xf@GYV59^US@y0G( z@TRovx3g+kQ4Hs5>(}B=IdF%A&V!-6@<)#6I9^Yy6Z@(JPyF2$6iUED{+1RNi-*x+ z1RnWW_LU9gS7Rc|zy#4)QtaoSHzM=hm3;WFeoA(7+`LcwM1J0ZD*GT>^uGYeZ&T-V z&o-S)L~M)n$SU?HQXkq4=0G#LRQ8mMf`2&v|{k)Ah^qzZ++Ve4Qg!7Fg##CVzS@Mr?}f3+9Z)3K2Z;kzQ)X|9t-(k{9{DZ zUv@r7!;SZ(OMZH><;{<0E*_w~+6Q4czG?Xrpix!>PevdKf>NREULC`A5{beluilhR9YDt z!J%XTVd#`lkQi#{l9Hi8kj|mIYv=}%4y9YVJN+$u-uL-_-?8_x_h0K+GqBd0bzgm* z=XD=4(A+GgdS4$|jP6x_)Aw5a@E4jy@#@RIP%G^BHfNigSz_t^6JKVT)nZA_EH|ByIC2nL-?^eVnjm3oSf7aFi|w(u&Xdfu3wBa{c`q!TD8 zKOG?bE6ohpAghM!+GnxJ@bD7YamU~hGmc2nYx$Ob5!P* zW;Vco)E*=b!`!x4x6A$^JakdfHCTYg7>QWl8=-ODGAkskZ1X@C0c_5N45xdJ``lmD zr*RPe++M>4`~MA4qv~oQlN4u4<*92JmYiZgXuc z9E>kHyD18Uc-~ywsYu&F4>#T4c9WC*t{Xc%NrvAp){i)^Ii1hpm87>|$~WD>-u4NQ zEM1I2?4Mm?B$r-kZZds;{;8wbbfjpHD=~f z)Ou6=*uq(Rtjrn_u#~;_`@u!Qze_gqV$IF!_h!N2&4>Jrr$d1Hj?Ir4%FMm3&{0kg z{e82HE_54yWcEkAS)Q-yB51C`Rw?1+%6L86jr2lyfmHcow`L@f#tT9de2mq26rh(o z#nz9}778Wua2=h}ZE6k&A z9wZ!GjKU398{wPj%~|1;$?Sr!FT1f;CNE5&yzfCmYnNB+{x$O%PWrW>iqG9bJmCv2 z$1|voap}Gg%8ef5KMxNzD)!U2cTOKrjCr$@`(7VZw z_6^fNXOvS_nQl5xhx<-Z3dhUn*xT;q<{L-d^K=%esUuc{4bs-l*GfVam!B>ty>mt$ z$Uk1UPX7CcJ7-Z+>XWiU`)xYwks5R9XLGJGx6VC6mseVkM!CfIg#-_m-8a#o{ZGI2 z8eDt*5H6}xqK2uBa84x43vJ&BZGDS!)sm{8v*KvyG&8WgG0rivXc4s5I#E=2+AMNv z67I4>m-=XNP#;DP$k3Oza^kCw#6H!dVA7JS- zzrD7z&>a@oIvnKT#hGwh!z(j8vM79N_bwqvr+G4@P&wA!=#`+>Y>)2|+m5kn#M)QM zo!|)`HK_@GyrOC^UJq8pyaGW8G(A-bcPDtS)G?cPtMrdch~(V|-pd_pP@hXsA>S2= zmhiQe_xP@f1B2243zkg7)9kde+^QyTq5Ox#Y34Ikg~+0C@z0k74FS(C;i6SKJC&yy zR~vJaHydfj)s^y%rMU+e%eh|41SH?^vXT|+z2~$!_6{dTg=13`L4|_x&n}JVIO4@a z^{=-CD?RpfFHbT;qsFBbtfW+jGm=odC#12^!63zio28feovHLV1*eZ)KPY1CICo5p zwf8=!MzK(fWXFiPS`bw23$U%6U5qIU2k2j)K`Y@MtuH_53MyY=yLxT1Q&jHVf7vxh zq8gF|@LrYV=db-HYSAHwH|{}3A%w)g>Y~y8_v_h$Y~Qx50rMg_UO{On=5jiEH*iyx zuzb4MB)n6VcD6S9SoV-VDXKFW&Ynra7`{2JMKQDhq5{44{2@HiWU0rE`bFWfs59}< zrJ%W@%k}L0>kR9pBJd8t$eyD8^U9y%^_ zILM{9I4WpX`FQ`O&Zt*KyjsJgb>Rl5w~xC(>WHW`h6`sNxwPHUg%dP-S#^Jn$jrc8 z)K1c?0Dd?=0YCf1>@IfS*Oq*S-C>UCMHm?ifb*(WOUewJezjC z@ahN3a6Uynyz!5jhdP&+PL)ey+oXoM0#V7@-iH~PgX0Hip~t0=23^Gbm|8P z`@%m(yRzZ?1H-mKb|Eu8SN3vD?2G-&D{>OaO4JrbAkVTQHNl1HiDdf*uLbN|cU~$M z5cY3(a~;$EizWN5sJuZPC;f)l@p`!YR{5E^p4aW+j=K@y4>4p-Z(eT2Jh;*vufLv1 z(9XE#wY=#<8E(;A^jtuTLYtR13x5u7T9fQKCswt*b8#wm>6og|9l1PxeAt_%SYSJ> zx-~4WXP7Mf;j5a|w+XSDfm7!$keG8Alq^~OXo_jVhiR)YrrLjEM>tZ=rK4iPHAgke z{v>1KmWgCyad1LFkiUPl@Oc-R4pH%STMYi^?%q&$!BkbDpJGUF+HRUO-fquA&Bva>m!y7<$YrBa=uwRC!@i1Hx^t;5} z-pVoU*k2BeO|z-7ZHmU@CJafYik*?X5^&jho;}j{*ll#+DkK{_vVD0)S}aK^acKB$ zk#jS4{x{sL*)u9g!MtZOY0&tBmG*=Thb6B1)PQ z`RO`s?J{Twat0_|&uRjO=xR5(PMD8R-LVA~VZ^`pavaTJ6vrQG413KXi;Zu9u!}9VW9Eign-o)FwN1w4uNPDW1wIH1}Wb z^y6s{HlKu@e1G#(vpa;bz%q8LXyZ_s*(0ft-(s;Dw=(~2b-Cy9Lcqk2Ph6T_0-51b zM4T03l9=J$Y+i#omw1I1UUuJ3!ewkBds@~aH%?ooS5xyI;S7b3VwfeX`VI6|AW+6b*j#Fc&=t)+_v8u2-1&QTS~8Xy5(q6*+;^+%77f2f)+$Smf0%b5+X zf=-6JQ?(5^EFj<{>_sQ2P*)!QV9tQhRz`tS)%Q=i4kJ4ylgrE3VSmo~EKapedAU-R zdPDERC+dPivf_qcsN3T1BCcwsmnNvLJbX} zRi67z@{q2)PnUnR0+dRnSPq{{Yq}*JX>8p%e1B=-k@Wh?eCxy_yt;ZFOXtJHexs*} zsKBE^yUBfl)tw8IR~{d3Rtp=8ux`E+cB_uePc5aH#s+Nk6>AF2U>ah5Uz2F4Z{`)>BN{Yl`RkoI6 zm3_@I%$xfc(KCMoR4wC1ryZ<`febg}?^Sv^GZZ2htXt(WP1O`xvIC<>aw>ja+pUJ= z%u1~WP(zI69KdB(!$oaD2}!|VIslOGGVzzG}Gi-v!>hvdwm`%C8kM*UBs?(zyq zitne_5N;90|6~nM!Xtrv;-8cMBo~YC{};#HFZJMKoX8_5hKp_ya^S{x<^b&2p8v_D zryKI8fs><(?_kb*=a7FM;6INBoM1ot8$6%KBJZxhG9w`2{^ngGe&qT?cQK51kHZ?!9x; zkDf`}L&Et_gtPyjm-fHkaVEScAk0s-@y|ux++CiC;e3FuJ(G;B3eQIDpLgejkmRiZ zu1|h{adu{Adt2%aFlldv|A^r3*Lx&=#})LO(s%8hl&ATBxu0};2vHaxcJB`$xMhB{ zKL6)Qaru#E;i+{dvQ^gjk0`TuMqR|Rrk-_l2AB-8MC=&%n7Gv(u|?f%nN(N@ zCWdl*ZK<5lji1tDQ|7e*%zQgPxhQENo!+SYP|KP}+Yf369o^(q9pT7Q%14xwFg$Dz zD(5GlHZjJYYP=b-i_^(d>XpNDIb><%3qXdL2V0NHneUdHf|4?sqYFY04`Z7J z1fTpWHS~>3Ia~~&5fW@I)Ts%>6P|6a1e6iU&-4{%2gC2ako0e()tX z9-|pz@?7+?qzVWw_GFe!W)~KQ3!>gnBKnK&$oXbu>(*tMtprt)Ia zG&KvVDA?H>$W^!U9P>!D);k!Gq=u-jaGJdp^asO@7rzsO`8_U=ZSDTmzNLQVHcBT> ze3zY{C8=>E!T>Dabt#YqJn6RAC<7qvg}+5dBg$`1r`paB)ZN2z+a&S%=sjnTw(HHybp6&SheA-4^}H za;@i^;5R2fN7E#H{TAAYmz!^PtR?-@aV~|{lI;28T^pPajI`_Qn08QG#YQv)P_X9k z?>OTy0s?aqs;jJ6{kM&7XQU3yN+}Sak5&y$5NMipoDOZen%%<|7Ii&NGx&4)(jR)XVR~K zCt8EGiaqdP>(G8fnzfmtnz^^_UvP*{amBA~w3|H}_YG4$PSdAh^`ZK1JFk=-kB4P~ z9f4NRORMV1kM!0(5p+mJQ_~z)W5WHQsJ}L&AR)1J4azMd{c)dt?Bo80$-`8ozlU(B z01C?*Glu4NKY*UlK|7^Zf@MTojOHX@ffyzv$Tv6d{7uF)Kx;2j*(N=DpeT`a{(1d41458Y%NkPCk~? z!8{T_NXNSIRgrep+g}ZU&};y!5sO$DNO&b5LgMZ(dd^e_pt(PlG@c?$nl6I|M9*~T z=IAP!@=I`Va4P@YUIly7T^pXUh+hOk`OcaiL4n$sUvq8iy{n_&{X~*9NQ&jp#sd2- z4?2HI+IZbwtS!YUik_$r|IRNcM$+7@%N(ynDG8DOE8XQvpv6$u=g2mo3s-{wGHxUo zla286`o(}#(;FRFT^8b@aVs~bD%gSv5%I65yx#!IwUQGpib4B79352R#RK6iK&b*0t*9+Xh4VLQLE3(lN;++ z@B?~)?;x|%H_f*vCG-g)2!13AKVEpJGAj46&3111vJ9N08@E-+r~{L(i>W;TkBs2M zuNk9Yj`gKru59s}4W%W`Yk}jTH=WL}bs64<$)5g*=aY)x-J-N^po8Ix01{Ez{mc#F zN&6L;;m5kUHgbkfifM)EI`jGb_N# z|0RH%#KPJrjqrxSkZ+C;+HmRR6}`Hm--8Xt*{1QW)YR0BC{JidxH+_aJSwGx5qw~F zy0{1yqHL}=n0;*RahIVR{p|QTah@F0@3nc6nJSqQ?-UdH6(DC{FyBOzwc(51hm1`pL3TNV9DZ*%dGD>-ic=8V$)T{+A80m&fWQrM@$Wc{zz1Ey1roB!?uWfg zM8Ud?L_P%20=fw%gwLj|Av$dsqglYsT8f*ZWdRlxmBn%Kq5{1Q7n)6X$gM}&_5|(S z4ka{(;FbTqZ#`^Bgbp%t*+EQC@bK6b_xtn9a$gFkRsN_?k*ioQZs1ftly^34qFzqOV+)5Hi8jGIhePs z?sd>f*6EZtZ}RUboLA5<43p27;v**qr6Ae-sx0Z|F9)vH&n{shuP%5h-^zYGK0v+!r`E#Sqm+H-3 z`3r)E{^{jf~Idfau;mwJ7fRXUA7jy11#@9eiAr{C@!uuH_#zV<48$&eeTH+6Bi^I zuUa4~u6FB{3hibKG`PyRpQ_))3=*(B&Q>s%sBqh@lX>y%OJ@h|F+tTa+T#?%SGF(g zzDTv-dG9j(grv7P-a*0bKnGHB`+-O>j^UTi8t$SiU`4l1sp|W zLi5&gxmwNF1wOv`?cX_s@6tv8{vMPYFoW74@896U%Gpq==)Criu+^XsQ2%|7F#CLUl8@Ay#s9~?i~$L zM3U3o&C*er@Bn^lZ^VBCRHZ79@x`2xc!qFUR3oFBcmtvhMrCPIFUopsyTCJpc@;rB zEoO7IGHp8T6w$ZLA~*4nv?=W0P(9QE6KOJ(CJ{OPL*_0gII-Qd|G`tan3t2(c>Ld3 z;jUBi-_(QnyTGD=)?G?;A4qs0m(H__j~My?x;QrOd?0)wo%O7*FnxHJ$GqWXYrq2l zNDAtKv1w2CK3)SpdTS-Zx$)V%Bjm#yv{|lryaxAEBS7-(s(Ih=r#iJIVgNI;t)%!q z{=iQa(!c1%&*Fd%nQHDQ$lCOA)C_?bWJau5Qdmz%J7w$fK0>8KDON4Bx`0p$94>a5 zd;X+-EDzerqW?I7eceFnMD8YfU2JQob*VErxhPZ@h(wkY__EVH$@e!^vF1E|e){FV z&_j)}h8se9PV0PckK)M;+?CxG<9VgrQ8!{Odql4c=EJ{!d#)j*v)EeTbC6&}EjnND zY^ZNv=%cQw_1QAb=yMJIjgl&zq>WI_+`w^2C`2jKj{r}6QAj* zVBA)?5B<|XKi{kWeyfd=b`wXFwv!T5>o%+n$_jFv@nq?lr->(C$pbfxN>I_y-DOD9 z9UD*g+zIDsNe*_H8%`Pou=m^<-!9^`7D>0OsgNwcXaFrSp&HTi*}=-YOpp)La4bEp zw&T@D$eBwio48M_Fu%H7eu6n$BIg$Z@v1!Y-hd$KTP*8=d2b7kIH#aIcYbw7DY5JtTd; z3uaDE+}~y_gakjYpFUT5h;U0WPkBoFz7bsb;;7)k_4k>ftu0BNm`5iCQK4pPBPB+RR_-7&SBMeG?@HT!*|0 zLQ>U~63W&!hmhHjcg-1+l47HwgQ_WeF=&(oW^7%J=uWBxHlz!)w!yAj=z-eQ(OV8a zQ+_)PPlo~$tv%l-cxIEOk7B&cj;ohynO(pXAR@VLOvng^VOlZLGA!7(?p?sR=ytxP zaz)zQJ;5W{VQTfb_dJ|n6$NA-{=95H?I7cZ{yN8`S@p)T+o)}rk182$AHRx8-!fv; zc?P{I@%)rx`bujP2bwA3FZF^qX6;jkW7ZrFX>?}34b$v*pAR6BG^)s`CYKee0u%*D!0>> zIP=hhb|lo#e_Yiz*s8?CU6M6#_4PbRqB>BrgN(OMNdH>Y$@JoIl|FC9cRj{P$N&uI zy(|4tb%P6Eo46@Roe>U5_-J#)PAdoPLzMWG{L?mmlas}NWeRcbb_!ivTt&idrBdpd z*KCM$mxPm%lq*-nN2+9-!<{9m5mH+0MuKYTJ5u>eIv$?FYC3uDH29)+YW5dGJkS|1 z|8^c5NoH+$n>t;@4~1}n$gNu$jBGOo4UC2Enu- z8as2oiVV89wuS;RC6DGb`qdFvFt-VZ?1xJB^xe`n@$l!DFb}rnxGuNjs2$5jZZY|d z9j2imhCWAaJ4r)Fjhk5yT#CD>)og&&{d6G41+GIfcTOD@Hc!Tk-q^152q}{6lX%zk zhZG(VE~6qQw(7q1nY=}%ZiEFvnvMF=+3XY;<~Hy9TyX2a*xq`QJ9agWp?x7v9X_dLyAE->1}H^(^um^4vGr^)s-yaCxsg`2@48~n!bhIeKl@JG z3i(K3YA}H)-t)|(4HxS>?ag?-kh`Qq_FBk1eo8S2#T{t|@|o)66_12T3Z)nibW|*C zw7_4C@O+e5(@9d6s+x&G>ijX8>75ws%#{r|=P$#u-DS!hH*;c!S)NN(`q~6L2XumM zvX&U4D2bPxUTAR0_~}U3jhogra>v7Vt4p<+JyUBJPeW>mXD^65aUXCMcL6RmsB@e) z-$5etF}yBZmKAJ6-pV0m|BF9=-?3f(I)Aj~Lvks!eUz<`kKkaUl{|l*?On6|NxhsJ zd@aBB6fL+wbQxTe5oTAgk7kkhb+ghQF~RL47=Ovk_K`=%i}HBqPqlMuUE%_G65MbqFl=bwdr~dJc%* z<{?=1Y>emS!CPseQ~D%dUXyg8a;4)TU*XsrwHaZ8O-k{Mm%o^O6KCBegLdI6n0p5U zFE@y1a$(Ly?5R&j=$tf@n#9vFC$Wf4a-NHRpn8^E-UY2IFsE^2o#S^Q2IhzIVIvZvnZP~G9! z3~*LenD+^1@mEATMeH-7mLK236QB9&<3YtMm}-G|Ns(kAn|`8C5kJ?rI{PNB1sNU4 z$J-Vr z=2^j3e1lNgN2O2yJj+_=1eYc4mYFVv_wvowh2`ZAb~+C%N+cj2DSvqmczCpFIac`jk^q6OZ%_4S$hzf zCMKA1v2@*sm%=dQG!DY5Cbz~@nef#{kd1t+-umOBjo|!^D?>jE_TlAR`oU6T!d3pf zScQg;RCZ4VKbvTJ;U2|wO#5t`1Hu{R_lB?H?IKNblGjGy4uD2NY0Yzuk`TOAN`7@$NGssy!RZSVQg%Y2l9$Yn-t{ zxiHI`nrM?u*^*9s#v#^dA^x_Swp<5C1dd}J+;x&;6)5ab-JpcKo&p*jq=SfllH+SW zp(^J=xj$xE2seY=0f&F_&nEDEIK^bnrnuh=^y)b$ez4PwzXR`U%PXuyIDH1NmjnC$ z^G<$@;ayez=P^p7sAXwhAGH!|_PGzDl^WBG%f8?$83J2_5y zV$5iWG4Ol?5iv&7nXse-!k-(Yv+-dck1A#%NjxOAz1WMiv|$e3+c7LW2kj-I?H&HA zG^yCG1C-GIleK~hDIpE(!Mg|zNUoGwF{;=B`btz#)20Kt3c)P1k6I`qhrQClXFIR^ z%X-7*6HwRC@h=51Z_@*J4Vc4`lx2Vv$zt4>*lkr2hvAptG6Mfo!i5dj3BYh;u<5ED zB*@Wiu@q~);{(`~Xcl#f>5Y;Qe_#ai3LR|NDn2JhLgZoNnqcy}@){g-TU8mO`WR1+ zWZ6!KWQ~x>yLb*?+21ie(2C^bsWte~*HHYppig=sG9=V%xlWgeORY`S?6S2bVrRV` z)J`HoFG}|1W}I~4W9ledBfHeJ=1-m_l=X{WD3gk=)8BOn+@*)c$LrOcJ*!6s|Q*ahQK*1d2Q+1~ZK%DzY|Ydc%ZV|%9W z_AJ;-zwzGDq>ki7Un%emW}P_)NQJttS)eD~y+14%nl2$@X$2kHiGQ!^0gi2Ae{M~x z=Fgip9CQ~d)VaD;HN;<*S5io)gh>98$gDd?Do;d~uMVp0dq1r#UVX>%ERkbbpX3a^SBQ7EkApXflZJfTwelRLW&1 zhY>H}*YkdG%dZpR#9TFTXL}jR;a`<7<{sFTinFq0&U@b>QI5+t&U^qlP0bcGz7n95 zoW>8iO;3FUTa#k;UKpsx)6YaD)UnwH2KABjXK~{a_Vg-(2D3hG-U)wqB(&=!m*21I zM-;s<>tQmd57na= zCnqHSd|r@g$*13SwX)hXLm8n@qU4rXYk@?mcUsUSdfM8yigxLcohOjED;sUHQlC>% z=FZ3q1|=e5&~&qNF`UYgysW&O8Eg2cjW9`fE$XqZsATHg zjpIJNhiUmL%O@2PVq{*Y$c`KbXKp!MPpuD{ZON7;D-F`fk6~6rE}If){5HrpPECX- z$(o4Vmyk^C1TezkQ^HlqErGw;!0N`93ga>q+eR+pvw9~gP!>o$CE}V*4UzM|+21NV~X;fcU{eNLAbd6@eV-{diy`8eZ|+OY>U z!sL})X=t^13biVDzfVXgZ=20g49C(WujryAdT>kI5V zCBF`ZT}h!nL{p~rD!vMbb_j1rpPA7Asv|wQ8-?!jIZ68&SWWF)MOB_a>}aE!>U|17 z?Vpv&Q>mA(JVYidLadub*dN7bHt7bBHSO+WY7;3_GKMhabJSSXG+kfD`pn|EJYa-^ z*-!_%br6UTya<+Jd8}<^YR+KLA=IHr`A~mJ&SL-Tv33-2+l(Am3U9iVp+o-1vzwBN2oNIG=bnn|{(Hs4fVm zG231Jsk!b;A~`>ut9<6GyFbq;hl6SHbTVcI^=p8!?$jN07c>Zlg*f)*E%WBBU$Gk^7bJ3xX60+^ z6=o+eY)}kCBLODJBYoL2j?{SyaZmReViKT>I}ighU-_lblHbOkjP?_!OtoW zMft&RZ2zb-PpHjR;2tX`5uH;(L9o?!0o%Yj0j#+b`c+~ob{O6$PL0rk%;R0nh{#GI zGKw_5uI5F&y)pq;a{h=n>y0^AXP8n}a0u^X7+0LCZ46b zKgf0Gz;H8yH*&M%-3$roa0wUmS9`jnZQ@ni#72`jAh&T}q^j8Vq7yOQwD5+F<1;y4 z;mLJ!D0M183a<3ibgL*;=W)cF8zPnj^@c5(T}G-}63FnoQLhypf}AIq22a;yY2F|&RVk4G<$&hJHXKviXRl&4I{ znd@hO?(=~9@j7VK+kHZZIX>1pE@;_ZfAX*KzmLDr3$EvTN(Um@VeYWq6a<<^XjDGa zO7La8(o30N3cB)%C@WAVraF{7^L$*2JHkc3dfc6{+4w+m3ce+-mARnq@0bk+5gA~+ z1l2Kq+gN=PwfEXR2l{z=FMWDmF4>)M;o>%*o9OPnJ~L#`{2*F_=|UVFCSfMSR;@P1 z>Rb$Y^9V+-Lz2O~M3GhmA!O55h#2(RA}~`E*gBm#Y>04F6IU}}%CA+o>T7~rJw}t9 z=GaWeI-i}LTX;1={>0C%&8xgLY;%$lchIqM z7-hWsTq2qFG^YB?!Q=ej61hGi@wrZ7qI=0jxvw6#AGaD);;5L_2imE@14tGQt+PTb zS)O+-XzF++VU*`U^828}l94P!zpm<7liWqmb zNK?G=_h_~|!#jQMR;;k&GB_nLfB)^cPSQhjuD#cVU4Ri?CshB5FLhsAODOOYF>+FZ+r$ zzkVZ}oR(;7qX_z0Qk;<$-xkWcpV?R2rNV<@q@D+_=kBpp?lDj*d)4&R2h!LLDf6u|XM2%sGa*bQR@Hm@gDXyrwItbtR_Phjc*H8Y^3}1>aUJ$5syGWA{ zQ$G}K^?v=uufL}3k zNG0KB0L_qGv`f5{{~LdyuCkT_K%z5CXA&OZKCfNPUy~rPz_b{POog3)%R?W3 zZAWClplZe}?eu6P!Om~CH7rPW!WGsBe8y~tO#H5#l(^$IqXa{8B8Wenvp8(v4&)`x z$Tv>qqZ96!h_IQIo={k=GTLa_N*;lA7<#`_vyu0N2Q=wv1Yaj=KBPn#z--V^}sm;!4&2>3CP=p-FZ^H`7vb zVCVQ(I$UV~UDqn4Cv$&7?t{Y-YsMn}Oq}^MY3Bz-JUENV#jGgKhO%&;WRP`A&k^C` z#fv5=!7Td*@mxIqBy1&k|4V61EtaL$u13rgSerKXw17;>GJ6wnP5;-$nATjX2h^sE zI7_T|pF9~2Eo}oF0E0oymZYu~L*LS0SzyX;qcovk;_$Dz3;){OuFntjPTKAz#*^+V z2bznUbm+iX9)PPZ!(fYu;A8H9@|OvO~cg$e78qDV4FUY5U-dIAgqQ_^b5hlg=qRQkRA( zd~Nb!oDq_fhbrju-W=WPBxCvKF+NX`l#C1w8H_|eLQj#TbDo)e*eSu0F!9CY5;Vc& z4k>qeg2LcP)lQymf07ed$}e({Y{}->fw~6mB91ev4%CnjY})ck3LB=Ev~>l9aNf^j zO$jl*pu^NL@St7R&-Y^KXVAsdL&~|?M$rQ|ShM4Ra``Cr&HxE*Z6g?j4hn{K;pn~Y z^B|pgV*I5S`?sx3Q;i7G%7|OT-(KUr$Q{y2$3CY57VmX`%rn9zW$fcz%XkEwt#*`Y zor%|nL);eH{yd0d>z>x5RG_P%_oCp+99y2(N`)@Bne}>@VQ!Ln_j!VRS-+34N5_Zj z8KhTlknyL!=SXrBvQ<}|sP#-8>L|x2Q5NgL1$6{9dA~ht16NHjUN$R+7{-O9$rQIQ zFpc>l>?mBzt7(zT&*~H(LRI0~5$h>Cj=QzjkuW2NM#OP{B;IbpdU;*54*_0O1G-l5-;i_VP+vj#fP;E(QV zx`!bq7y{Yg0_Q+$(Bg}&F9h?hDo5Ulxu<9+W2PCa)d`OvJ0GysEahkX9O)kK=Yne} zCqq6KEKyER5--;=qv+m`(ivsxy~@jVVgA57SoA`1v|lTi7vgG5)S+Ut_46KKRNksB z#^ZucTiYsu7Qm)JLNM#|>)!H?cF~QDJLWa0K(IeHo7EL&pcxh_mQ9>_v!_7sJ065M zWn^eH*X`&eUAAo6S+^A?k4d9 z4g~-)I#r`$^DYRrcGY8WGS}5}lK3D^gujOa;J%prq_ofyJRjr~b3uZyrTA7d?r@Qk zuo5%HKnaoYo!VeoH|K&pd+QsQ-jdZw7-@Ev6p<+hZj|n8hDK-BXg% zy~6sTOWeOft3zN-IuB`TZxiP0IJwvrz_h+AG9QwI%GQ`r3fTdCAK%YJk<5nF_Y8EX zURg@DR#cTH%oE!qEZ9l`sUagpnCofwiPV%!z9E^OB!5gg`y}eBLjuls`!@k*CQ{bx zN-aeuX3YB61i9%V=X=wF!D_Mvfd?$p#*7T!=Raa|X@M#6b;m+H;tg~2J287|pyGd$ zXQl0p5}XIH;a&ISkGLvYjiPVMZH>`~S6H*H*61hQJ>nGkGiG@GrN~BAUTj`Lb{9xD z2K?7S^R(~dc4?=mV-X;A3nh#a)B46kd$~Jv87Cs8=%g;?tcz|c#FNZh60X4CqyERg zNzxVHmT+A;vJlYh{3A+CE4FHTtM7H3Oy(Il=tqJ*N{+Q}JvdUChwRrSV9y}2K zy1&6nXb0OA^-s0_<$Hf|8Yanlk>- zLbA=HpX~Yt2{JtV`1Kb8-*lPcKdrt%RmfE9(`07^*|4Rx-&@>b_8etHI84_uH$^=) z{bK8@@p2I7T=Whwj&u&MA$Hc6q+H#E+p|eKq*G_fz9La@6@9w+sh{Mx3cH_q39fu)j@KRM!-g<@%OsC^)J7^tQ!wg?{q5y`J64HH$9ntp8AVeQdgeusQ*9uDV<^}30^PkAz+|?-~ zb0HV52Csu)gQ0lSl#T7ISYV_MR_paY2<(Wam~Y<#qs$jtycMz9{TM>lqa+_0=}419 z<@C|NvG~R+h$@jR>dQ?8qs=<1Iv$16N>KYRD1L(|$cL-A&jWD~P^YksU;1ImsIw%T zxb)4RuO0lRsiAv1T36SEW6jS=M<>xXmuC34X{twzqTnhq3rkaOle&h+XtL8>yhZ_J z`8;krEf`u?^1EQ#KZv;d#aBL=AwjZn!9Yx>ax@{uVOwaM*nB_t#Y>D>!?<&TELn9c zL!E5h_e6If{}=QnwF|8x=gJwOP_C#$#)tQ;#=$)E*&zDZSy2=kZYZuU_ zfDC#Azz^pf9@=eARQrlniO z^+6u)YzX>{ex7bB2Kq5}0mnk(U-eGb%BF`ay~n51*1}nV%fMWe+4cJQo8r>Z3>m!3 zlM*kE?0gVEe-PU$2M0&x(SUI9=_6`*#3(P1$8~0uBH_i&)mcu!GuIwAxwOlCrB~hL z3s;}XyUAM~x_>e=!za@e@MN1{avoR)(4wUC_cx6TQ`~k1b6(!3Khm+P`o=mB%*_P5 z9S7e^3^_Z~<^22u;P^8i;E6;81qXMYt*sGtSpmCWFI_zTtd58# z)T7QnZx&Dj`-U91Jix=8PjNq#8(ynvz5xcSU$^vseazKRx`iZ^be#7%%c_}k4Q{&l zO=-K0e~W*94@8YCyv;rJDJL0x0f6Ek9eBt^S_nP!eDBUxzs-A~XE<}?-d4LPEHOs2 zAh5u2+37Dd&<}veBC{d!^ssAg$Qa`lq?&SsR4k)15zmigXcH&Hq!V;ooJ(Lmx?c0C zk+o;ct#NjNZOuQF9W_dQ5!NPVnK`ZWCGf!=IK1M6G-r`zO4wSZ{o>>v5b2O1YIQzy zQ5ZdiCKKdIqX92zO?W}0EME4W+%J;Y{vLrH0uueEc2N>bxet(FrIi~%OGu2K z8e!A#0f=z|Bp#aO_OCMdW?l}qp(~&Qf}}*R0gxn)cQEFrlII~29U5rbl8^2;?IG>d z%9RV<*faNi2_6T^6M)3f9Aw5zUyCSygDDAr`xh@h4;Yn>vNwn&Ji?9~bY)F&qM>~- zM|B!dI*Gdl(8CT`>Rh;@$M1Na;r~Q@jg5&J`3EpwK=ucK9e469)K7Z-x#_Gm-sW!F ze=xlHl>qlkj_6DO|BJL7QMq`Ja1g_ z8JgJ0KE%iRvfrlq2}FBL>qtkzqeea`NsnEuIQhjnri5Km6!GCC9P@OTbcgmU!39{A z%7xdELXh(vo$UQ=A>*K`?{_eH^dw9B^TmK*vs&GBDkI~m%1=fpP&PBe6s|XJ>OEvO zehDF!a5ilD_vgw$wi$f4$7GyvfW_dm>CXcI)6vS-AN>WUe+dU_j0I%mpp!?~({Twn zI`_IU5>HM}jA)jx0C!hw(LkWwRn~(z2UdtVEDK=q7}0E(_i^ei8v`P|zNQ?ZR7>Ea zb?cj zZqt?keWNU?#p~bFHRc>@Mlq^EP{r?scNYG_4c2tALN5jC0VmFvqymHd8l;IL zzk>5!X#wnyJ%!vNbC64Fr;AwDoLO(RA4I3)sw(-ziW8kh{mv`u7$zYg)wD&e3vmT# zK}H5(hrDyCcz%#2(~{=70*?ZC6a-dQ$M+CQ3{n?3wU?@1gGq|Xb`WLAFS&l zpRx@0iZJ64Av!l7l{hM}=ZL4$&5S24=?|!xJ&&S?qAn8O_nL&s#2TQ~inj9C`9*#1 z<8U>S6G1D1IJ6Jch+I7&pQf1C05{!sl!7OQfwDV2cRi}(VOasy?4)Mz4E!}_bVk?*8gmUYzh?Pv$lnFYgjN>+~%y#brsFqwCQPtU`w zlg_6s2pLa^9ZpewS;{_(P>8k%Q{_^~4N)CD?z)b##(S^LGOo|%^cT|i6o<8gk|s%q{RFo zWzLYY?txNyLABoTiRE)xy#uq(e0z*eVg3?a*(j8Fqc=cOAJKh|f$0l^>QS26t8`NlH`1mw7 zo2>{(1IvXQP_o>>+t?id9#+r7Vciyii2%rp zBluwt64u7=Q*d`t)t3W9?~UP^u^Q1Ml}^K69B`tnaiHF>y&_LC`r+c{W`E+<@Bn`S>Ez}rTgU1v6}DTBj@Pb&md}Y^y$VYYq*yeqmylx)%!W6-{lqcR7Ep#p9ai44lI;&6POtZc+G!{Z46Xi9ur4O_=!NKbR%*--Zwul%*6~L{hglRfq$_>Y}j_w~3kbIe@ z$Tz!Ia}5$P(BBX;!>)hO3VKAv20|)OLF9XM7*laG|IYk z!0fn@_G~(CA@|}RG0Y5%4$S^JVkDnwK&|XkL|r~}k;CULJ3(){yWFk!Toz%~Cc8pB zJ+oJR-wB~P%p*L#YufMAY;oi`>*I;%ee4`nZrbL(exS7SLp&CO#~tqjD6Mv|JXsq@ zMu%%^kZ&RQwh`^id9uoIT1mkw# z>$cU4g)X{O!lP707h6s80azh#UQyq!6U21z1b7jwI^~<>tnxl3;5eb(M|_A*{yOE< ztl20j05TGyBu)g$&Em9KeDEsx2q>yd3J}jrds`oefJ?F?En`f&GdP$UO@tlgyt+AO z2Fz0droJ;!-^3$*;1D$-a}pB$Qh~AMRI>dlleD{h0IlF*jiIF&-SAevqQaObAaDFj zcaexp;1~H}8vaS=4}B*ghxXl6JTbLPiC0U=oQ4?_Be{PgN2kLU<0_6zP*5W zes<#+38j3|;d!z#{3}WHk{41*tP-PzX2|;btF4Jric&BKdg=F77fFn?Y%c;K2R~#- zFi?mn1ZuE_JxKvGU@xIfbmCPJg$C(DjeTX_x{hf<=8^#Z`2`MfEskdleL4F@?p)AS z5A(x@56XOvW7AC3Vov#$I{FA;vHMGR4+(aFDaJ*<{K}PH$=M{t7!jB?lbD$Ji-I|P zsR1>ZWV2~AHzl))ljdBV0-Qpa5<`%D)~TvSo>j>~b9;MwGi^62%hKSrKkU z9nSUcQ*YKBU(`*qb0F)82nSNvp5=n!=}>z=elAV$HTGL~Qn?7r(_BEzkV&5s@hqtz z-_FmFZfIm=$<`V3(!>gKwD81S5S>x39K5%!)cMwQFnM7==BlQf(AY1V?rb#=EkKkv zOB5&Kn^|4e+8R{Xkdzv;Te`OHP?PN30oHBq(X0pR5D+~y2M0F(|xdOa&1xD$-J z8i8xb;Fk>bmDstJvS4O2_*;)3-0@1}V(03zCmD#iV0YB6!EF$~f&vF5!LKxMDZQ}j>pci9Ik02`s zI9A`oWy+Mrb0sa6z4`=VBd2uj@8x(%=1?D=k@S;HB|9U6N+S#t#PU@HVe;*)P~z!Y zmG?1%M`^tl%ANcCK1&if*Nv2#9W-r}-H)W4#~c^fq8Nz+!ImY9>>jJ-h0chW`MwZC zPr7(9vx6%i{~PH0;LNZZN|O)ou--Rv$7t+(#UK;cFsfFq0a8mXw?HRw&oXbrvZD49 z97wlw06@RpBzv(_cmjtl+K1RSntY$OW=QyqcG!>DI*ukCl&=w1Ka=Uicj&MG=o;^5xz)F?4!~fxRV}2ANO2 zo}c9sbbL1)o8eKDQzg|4m*LMdbW)Jx3J{=E^ktCGCdzRTZ<3M0Vc=s7@_H)W(wh?? z7@pczjAQdeO)WT#H()lX+%Sy+(L_T;Ih+>B!d(B!4N3b5C%z;()MZX2;mmCK$yzuR z5l}V^eaRK$I`fA83J8!=pT58Gicszl$7xN$*}7y3Uqbw))uH2&aZXyj*sO7fTVDVLzvVjRhr(_}N!Xlcops0t0Ui($a% zg?=9`flT8QiQ@*QjPN&@iu|`w#^kKIPgf-)!DJH`+H%!Rrac$o?Ow4s-K$+P)qX?{ z%3^}_OE^lUkB(RJz?4%CQID@xr)XolwVCOW{ka_mPV0}5V|{p#E!H+a z3v)}LBHIl9O^~;h)z`{I* z9RfH#0%hFQf;A!~=xAU(V+3cXi6jgM&XGMrG*j4^8RlV>o03QB)$Ow$Zt}2G6or5M z=F>ftctRjOj^K`CA~qjW;qQ`;D)Mo^e1P#r_BQGx$4wtgFoz^=uv4TJ){KaRY}#Pk z3)cR}j#4;pBI<&W-jeYkFl&@1x;c-|Vg}SnqjZ0H?U@nNyave{ty1WQe8&)2o6n%4 zW134skmsU}=~j7M&A3NFsU!@_S)ENWE8#5u^w~2{*5)Ipc%b4G@%lmW1kk!BN&ETx zTf*-4u4CXTk^B@oEGX$PUHAF>l(xV9rmXfei@{+^M33O65Dl?CLpEZhq<)_gg)eBM zhDIa8E|Gu#a6+!0S}x}L=SqQUtSf1(1MzABj$v9Ywtb>gjJsGCf@rqhn6pE)a4#l9 zBxz7P?|#@gM6R$M$Kpaq(R>CCT>o__NyFZGUOTAB?$8z0x3BG{QT_MXWmWts#CF>p zuA-j-%qjplq@r;y+DcpS;+6R0$+A#aUbCv z^)o;pJi@;8EUp3Bvo@JbgItXOV1c4r5%C7YVsvD$WuDIG2aHfCF{6#Kc#}qTZQS)t|lGwU+V1@e6mE|R|_BrI3z_9O>EInByb0kv3#U|g_ z9yK^O1i49K+28(XKLqoXH3CEuH778@6$4O8Y(}hH(&?NZcID&T5@ZBsvxaatGcsP{ z%UqRI>%}TOZOW8vy8yH)tMaZA2yhJCe#qs{208JD?HG}^Y7SMpSqow#moD|d0B1-( zNKzxArTGSTiK~IN@Sf|j^ivmaZbXOeRJo?zhFv_JC#YFau25?LC?3KC-qs)-Bg^P@ zQ&Zwp7V#k+uV@dBw9eH^^OCY5F zQb#!(8kzcfk_Sb9B(92aH+-`Fvq*ui1Rkg+S_Y+Y68V_{IKM9@iuGSiBz{IJmDW4R z#QaD;_?7FX8q5(?!wE%|fTM~T1O%Chp__3jHn(5pJuJ1Q3GPuPZ(bG|mW-vZ99*{) zAg=cbm@49i(44w5AKlKN)^JpTlL{_3V>FA}^eOx5^R>~xCofn^Q{y*!oMzS6i&@9^ zS|1>4Ho1@({E$ugCLDW!=eL+dFwAouY#0B!#xw_x=0429$1slDC$h{|VP#Sh0gWSA z+@(NKI1$h2(FF@Dii8rkvo%@C8nu_&Mwdop42`3gV@umv*1cFu%3EelA7yO#`g%fu zxD9G9&aE*O#>@ty`)CE!WWK)|ptg?Xe2iR|#y_rOXvik&CUV>a;2?^_uSqslb)1xk z^Z-qY8rqc>&Cu*h{=NoFSvO4Vmrt)g zDd#f@D!Q>hs$Z4M@%TV>k}4c8+6M4vDMrj*N~b;y$eR5`gb;(u7|7j0m2=Zm+>%yp z9*fO)=0@n9fH=6KjySqGX|i%~>S-5X%qlb?%J2%;b<*({ zsnHL_4V!+1TY%ID`IHbxP7L*oOt?z#lmlX>izK$nN6_D~NzV(Sw`PfZt{8TR6TIt4 zF*66(GtGUX_(jzCX-8{cjeNETK5o1DsU2u}YyW(~=+oH(6Nu4~o8+7g_ z)M_cXRUDx@8upG?ZuRy?m>f~So7>e9pU*sPrs(?EAo^WV2IP)(yy!_bQlPheg%zM+ z5CsaNG)nFCtppe32i{BQCFIOf+3F3dKO#k|8erMFc!lb{!_SMCorSBd)%w{kCxZw9 z5N1v=P$TycEF6WYgBrfZwnbSqm(mubAslwAxG=8tH^|h<;iqpKNxR47F@KOn$ziUD zgGk_INq_{tRbz7zDvzBlspfVHD>Sr!D9Nwj6=?)JsnbdQZVQ{yJ~*O-o$Xr(a^h+G zQ&Wy?#*_VY5MPtIFLS<{Z0d5R$!_DRK@u7U0tSR|V(x})_VG7s(rrU39Li%?`PNL_ zw>wHs;Z68smi$*O;Jc?aRu|5OST%R38_vTTSAR%f}gOwVe#EfPgXD z#z`dc&PiNj+G;7VAdaAr5>xsw2BAa8&Els6qVq>eZ0-jrr^_g(iL>2CWTpj2z;uQf5n+{_NF6so> zt*AR0r;ORI_OyuPy!?9PZn7#flN}l$mNCzqwx`Iwb3L6% zdE>x>^JNFr1ZX<~$^x33QZ|m4PhJ#mBq^G0vq!0fYjXU!%$|v@;QP-9bwpUn+iwq>79vTe2rD*O`E}+i7$tALK!-e0zio`uY-v4t<0AB3 zNK2&6^#BdelpTSdyX+%og0>XBC)R)xn~Zz}LmkigF*)flJ_D1E88vyXu+`J5rVO=Q zmv*LI83<+?4bep5hOWa~`Zc4z4);1SnPHynP7TzQ&9ZHUxM$X1k{{kcUuQE|zPOiL-{zssvkm1}r+RztY1nh35w-d;urKQA?Dtk-N}3Vx&AlAfWT zcv+E-aFHEIK5g834zWei@_aUNSZHs~{GSh0EbnvChhDEPZKom_*gY_-6S@k$gf1Br zGxs&lY+i1;Zjo~)%{NE%)-Al^%TKe-J};=jU5-tm?sCF#Q}Elu*u*QGQ3qM>8L zTh%ieDI4=l!=tRlJbuAY1a{f#t(r_I)@kT9quj$QY>B?| z5hd31JNMo9XqL8Ewo>RWZtRcWRk1^97KVEFiUD%aLcXN3S+v+xl7{WHZmf;+iQ|r1iZIVMfGI*g&xim3 z{gfl;y;S7NGK`5uVDv_adq)NCxSi%*Gu3UdJ4}h zCOOF0FIg?OW7pZdUPPF@6&geg2tp7$a<>f(%TqE4$vs;@o`f*H-T$=V7x zFg}q?`MA+#a2ffhV2z^}CQqGKBu2HIZr#u9?@QVXL_4(-uWHOFwtdOv^)>7XalH+I z1N>-t6?e_$@gS&zt59Q)JlKVFD1V#nyR!z5#`gV2Z`vRbpeq5BP{1JvwFWe32SaEN zBQ3N0ixJ8jjHYZg-kE!S0{DRaRwH)qeBzGjc^~fRopXi`ywH1P`}WfrO54}~u#R*T z%z~qV1d{PCc@MIfUZ+~tnG9}w$}~Z^G`ve4*m2BK2psTIpe~F7R*vnD=$~Iv)9G6Ca{w6YxLB_26@ zuHjb;Z0VGICft(QMD>LtxD}!G`OH$RBO%-th(j8B@10Wt45*zIU9-dF?h2C$F0_@EhB}XXK)s95rcaJW`?|IL ziSSA4pe%4+EY7I*DP8Yj=FWT9HcepiUJn{_5b=(#nw*`5xz@z+ZHr_z5)}^V@`L%m zJ|yMUJh;H7Ck?n#LZ1bJOjWMs4QtM9(ml9)ChhvX4G5L0ldrkz0lLljO{TZh$(>Gv ztzz>y8sr*H+Ie=T8-J9;QLr|g9n1Bpw4!@BrxeOs$oH@C(cS!O4`XLjzDL@KuAcoL z8htC(CiC{T?uhJmz9m~!@b`>3-9E;vn=RBajre}8R>`2R>5w72%P%u{6{R!d-j09} zz{4$!alKuS@kxQ=WNxBwHe^%yHAhZi(0hQrCd0hnUSx7uCvt3fp1O{)+V_IND3jeS&d&&5nueq8Rz#rbkUowE<z32oe6 z@4KG$e;BsrgpINe-TEo&2AA=E_UBHv+G^s>Y9B*k+hz4g*E2*8*jn!t7lYKE03<1~ zifA%(K@t^xbR?>A+J}`3P%AyI-icobnR7fgtb~@xb{HZ5Uz&w17p1a$)RX2^htR;p_ z#dL&0zzvOPYFrz_<*{};-~uZ%hvRv)Sxi3dYpx>^ZN$+{-04?(8$+r28?TQ&V)b@4 zVq7M|WprZ`_>I0G?H?qKP04gm<_A=%G{fCw@#?TSbXe*V*TtYr>Q8?eQHFoa+!yAS zwqWUNKl69-paIRl$L9R3741~yhCPw5aqUpa*QfHc0WF)C`_$V{qUOx!lBCgy=e`ZS zNoI_mX~EKJY{WNGCvKoP>XwJok;f%6?p;@mqfKZ0?P_}TgUhKTVk_k$bLM`ochR$> zSK>=Z1pr_T9|Rhbi>&9X(P_<|OoZXkH#Td>-KI?8YUwSlzlB-oZEs~38`fnElyzsp zL2uTby*!#y_BUm&{3TUlXA_(tPt@emdW9WGAyA)S@(_n-SEW}m5;glc?py3wVy{4k zX8eF-abqze_K{}XCk8n!-te#d-IPIG)H;j>&})AWsB^S zWHf4P-0H+foQU?ETgLDhXiGW!E(ayQ#v#!%LnqzpTdAVQXudj7I#n(%N@fjA!T*$8 zXczuH`#Q$Ek+3ladqkHj=*|9GrLFze`;rB=+7TtTD{1=N+l33Ok8XCJW}2A!lAGSo zGo0s7y~AhbzW>hjfZol%3nhE0@E?~U5&lP!gTFD9sF)({U9jqNcB2ljJKY}7 zGtrwF-YtMTg#FDhf52X(!_eWDK6yE>e6!)~->$YCjc|5mI8x4~p zxq%6jd}$tu{Dq?Ur)TF+KKabvIMdu;&`}#Wx7iM!o7kq({!yW-Zpu~-@k@hzcWB?H z8u2GnG?9^~RM)^tHv$q@qss);YM`u#7PIN}8-2yTw^J%!PH&mFH+N?bwiRmV&CI}tG+;!H}Yv2=5}W-JKN^wh>aUjI#20I zseEu5VN3#6O-+FuS7#NR-Le3$rZ0ZO$9+5!XPk1{RnXgmF5W}plSmST0X>@Q)eZQg z;Zsgn!_SfEEqkt}{8J|yXuk7_Ym#TxdF7*P!nQ%a*^n2L#rB`_d^{HQ_Fm~_0mXGp zU=8c*A*Hdvegn}6&WSLU#2Ureuz~^{*L0J;B=+IHF&{ruaV5ds*|;V}8Xy(ZP)prT zMnxoExNu0K3JhyOA8kmT$5%p<(=6X@E6flc=@sWqB%W!*D~#3{H+RSE$g841BZlk> z8Rkoi!S;N1Tf3G%TtVeu&N6J8r)4OG9p_aJU}4`ZgQ;eES3RAD_?n9^Eat{b|=2L&N4g5?;XZv3C4}`$a-8Syl1X zC%i)S_B;q%kB6f~16q1PV;So37;jwnSN6>FN5}rA4~EX$7bbPj8T+SdFH<8jpc?_| z=;msaVK(VEW1YDWpXyol-Jf=#wwdJ9lPhU&mcWw%vI`b1qFx{&`gbMDOKiW8NT@wb z#)1m;4N?}1QT!So?RjbSx`=Pvy4|Jy_%&BO?~m2idWB73XFLwud^Xw{!+M3@7}3&1 z8uAVPynX>cowZSHo=-_SA+E-bE$N}viOBqfoOr*;U+J zb{eR@`<2F+YO^+xnGk*?gp*bMb;;St>?&Tk(N?L!HrKK<=yrnF(}8G6W|L?D zKdW&9=kba+qq&F33Y73irNvz~Kujrn;)4~`U93V?|3i>V0Zx(S2k)Y8%z&6-vgT!+ zw~x32Vn8^}Cz3h03~*=@%6PLS7IVWbIF>g8fu_wSr!LmwP)nCgSy5v6)Vski!>+U( z_lWU1BZh!;OAsjL`PBvL*(;=4itAI4cgLP5sbxG?f9fW%8wqU@CCrgszM0C}^@04ni(JswA zBsX(Bya0iB$jo)L2HO>g5$==eZEZ+nS2O)eHAYk;N}ARdRvmkNNk&Qk@oC1h>R873 z-PvDxwpSUu<@ce&Z8yb{eFBh&Pd_88`q+y=lG(=Eo;jPZ_SsDq_I0ETs}54*eF_tr zVRQWeP@$wub9_Fs%UW=?C`ab9{E~SRuIzXzl0_9LGWC+4WF_#wCE!0+wIcbFf1F^E zPfdW#H676+zFGtFYx=Q^ErDx+k386Z-Pn^G`!54i7<%|O~b21jpNExYF5 ziFzXdJU+ehPA|=aE6u%w`2W&|x09y6D)vU+Rq+<8WEOu^^Ot=jJO96u`6+kSo;!Yj z6!Vun@Yohavg7)JNrp}SnHvZM688k4CY|Y?a~zWU7i*^92ev+$|9v91Fo0iSGM;LN zlX!RQ%d08e1D?P1@$y;m{5>tvG$>^%b9&12%Ve#0tvt}_JY&CmU4iZD*ZJ}>^L*^n z`PjkOKRYSG!q7FKom4b@_OaIKLJ zfJd67mlMJ*2G1@+{E>a+pVyf~jGTS`+5BS(@$V*tTIt6D)Xwg!QaszR>D>_}yS3Jw z*Rjgh><@tQHy(ZqK7{l;DY8L-+o`hF-d@@b zQt$Rq?Kk%Jd2}vQ{&yGMQevWqp?XT7f9)#%SMQ4QFgL;nf zN668ZJF;UXpNG;qD$YGL6>EWn{||-a;WIZRM9~RAGK&LuI4BM%OaC>p_|v=p+4zsE z1)w?Y*7s(Sh+-ZfZ4~6^hjqo!0Ui(s{$U$-l>@>|fQ!ue*C%f$M2f>+4SbdZh$1x{ z?Ue5TaehrLt$3}^_f8pg)iH^oVH)9*<3>nXL#LhcZcQbn@YlXmW}(9)UzO8FUP|7c zXd$(A<={X9G`;C+>rr0NhQ04KjU52$&-&KTkorq>Jr(M+FjWJGifa%IR{;hFBY-Zf z+=JY zWoHML0CLFyF{PBF-Oa+51@I#9r?Q50hL%3{Jj)T^s}0mGHBnKZbqIQW-xTT0o+syM zhor~M0L=9tU7mpAU^d{gAodl^*KiPU@O#40{;OGgNVwPqbh6ZRf2`%&QEFezl;6kH z>o8dBV~f2JO0`~zkrH5_AVl}B1tkUCBw$AyON@jT@3gNQyG+YX0RjwJ0D0^L+G1N(Eics;J18Dp*sem2*GpzSmq+^7r zOKX{d1X&NCdSD5J3KJQ1)4q?Y)gVIKdge6e*vE5nI%$do@^1{u67G^r5^0LeiN0SO zdQ{rL6tf@ksD#LhNINgh<#X+@pGCUpd$!vZb}3?WJc*+oW~W}(gADc`1zWoxPH z2aN#bEsHjj?kZp*wCsA3&{xrQ&YgW0co8!FcL0i(vim;69g=Bth;53rO#dus6;Z~B zG(kY}U=UcB86$yM3pL5kRQ~}cko;2^X>DeweTbd}*t(V_4Bmr9lhh^ES z@O`>726+c9bV-2ka%yZvwTxtG&~`tWG?Gm=@!+hgstP~KbU-g{z7w;n8rOaNdWb=6 zzu|ZT;H;2#Gt>d}k6@~Y0_H&%d;F>ZpuJ(LD>~*kaGOqmF@jjtkHBNB?%4N4cNYD= zC)xDF@oJKsKWV6`U;n;6rv$kI+!#9t3+%g1Z9Tn6K`-B02mj++fD!W*@Vw|gLE^06 zY>*)0TJec4`u;PXLChAp0K!0shLK) z!EgPW8Kw-eIoUIHI)FOFbcIb%+}TNH4OVvW+MoeZFih1~1!yRJ>gbd0GQF~NuL;-AG%$h>9_ zkbK#4?+R&8fW`;4Tu99?Ev1|%jk#aR{?14+YX?+v@AMA`W`K71-9_LhR7Z!$2&xut zl#}p$i7tE)Cx86Cd1f@;U#$Q&OmS@d@;Ku+H#F$kJ2e=;G{UmQHI#+}=6vtBL*NEL z1t4AjaYEQ_j`|AgWh3fM)V&*8iQ|4D8N{;NKXW}Nw~?vWm7%pErFSXjIU> zgWH$6_n(c??EVJ0cj4aPZyJ~&_aXY+VrHh8W86EYMNgwDo5YKUItKvjozNj>`F=j3 zA*{-ehJoJus*m?kX-10~M-C(ez$8Jn61udMObam0 zXc|mHz;9*pcxZ!umB_2!wASDr4UE&TVB$3m`PKQo96vPZyc|rJsE|FwtKuT{sb}>? zP*10m4Q)zCF}?fEvj~^)`dGD62lO5VGCC06y)9<3-+-e=gkIn+;8Q>W3VkR0>@1vy z!O@TnapRBm3nQ#+IRqPOzVHg~m(Zy^+CR&V;J~5-g8NyWVPu8F>R9aH-qkU)d(yaO zxD0Cy&nFau|IAO#D*6EijQXUTht)k zA(>q#Z?WXSaRNHDqaPTL5G?^Om=$8kh&}ExhD(kG_p|7`;cB(5o>==D zB(e?C{U}(!0P^9vu{qALj>KRL-~i)*7xq#{d$9`@%uJ#5hv6bL0yB?(GwLS!V1abd zv5#}2me~J1(ZcqipAU_P0!21pp&kF8#3cSAwx@nA{?dMw&@ZB0A(R+g5KcOhGsAZ1 zCD_G)7iKQIuw-C^ux*`M6py=ze$*ibm3%4ZK<;HNLdh@h=3}HPi%G@K9Tc*@?O?L# z+426Q)_uW63vIA&IRwM2O$AW$A59G$NDX;LfFkR53Ij-PA5JONpYGFqRIH^xKe@ zP9{f3YGE)H8e=XtGc`VObPBpAmc?^n3dtXU-APBAp?(-H6ZHqJFj=rpc^M3iiGJ|b zd{GeV9k{=IA=QY7*5_HjY+38WAWjNv*+z)}VLcKki%%w@7rTC1{-V}P9)T9c3XNG1 z?>Z0K#|K%wq(QbCPda;dQJ3~R-bGIZam3@+_wyvFq`-WIx681==(hTH$%!GLT!f}c z9DG{t$B-MiyhhL>v;q5q(#lP#*RFyFG8B<=@G<)$+Mr4>Sgc$YE$k*oH&6W6@Y@X5 z_O<8eGy6ae8pTb(fy{R@nHYilm5f9v-S~K*FDc3k&bGiTt2RnL?9k7qwRU~}TNH5W zO2}2ct&3mA2m2;Ong(r(8wd`E#?a>3o)nXu-)TL~sBrf3+;c~&Vv~4eZy3x}nU%z+ zNFus8=Ld_+&fXuo##3(Yh!ZrYR7`{TH>I|Yl|BN2$;!pnasuwW9T&@6slsE<`R+;k zR6&QGPt>Ng)?^<=SHnQd_)K58>)ZV|FT$R!S8Q}uF2kJ5WeZUt6uW~J zCENb-bNFAssZ@$NeP3bb5fb~O^VMeF&WGakY1DPpm{k#<)14p!9fCWYF?i`CUf z13q-{E4v@7t4A(uUA;M~h?;C#_9ufZ^Kaoid~kR{O#Elc>f-w1HTTsYs{jxVp*lHe zELJ^xBv?gv?x1`j(-ccdHAl6&@fNErtzn= zI^CQq(JOcnE!uc*r(G8Hy3iAGD7?4&z61Q%n23L-n8RF*N9vdaQ34^NI`F47TTM0< z`xC;TH@GXn2@ywuTLDhCdB^Jn;Knpt@wlHZyixJU3vD}V{t>DX)zKOMMX`(t7^xSz zZ>13fZtAu*vo8PH1+?-XJ9WS$)QuK@1r z|8{Ux(0RS{_686ckUZkm)6>&3Hcr!O`zP{l=Z~VF4RZDL6t_bX(vJr~;-c7l&A)v< zKlKzINE1&^;xknR(mIaM{~73j;P$YcV+sF{+uZ2I;c@{Go2c^sGpPc1DeXi$hYU?O z0p4;ZKw>h z{`=%eTOVK}I6LLQXYG?UGR{USRW0%?eg~FfpT(TH(g2Szrv-n^h=#ljpP7RHa+8M; z$peL_kX~cAD(Ih8%Xs|&av7u7{^Z~2|34x2|Ie%v$?*vJPY4ftToHc2%gdWvT`g=K z`%hdSVg}O&+=i5umEWxNd@x5p{;Hfj0yJ_eNr;&vxk)kn&r0dfbpsa1-vQSJ{0aZd zlCqnPc)zH$=`+&#h_MCm_EH4g(Ez=Q|9L59(_pv#+U1zXzIQhzli{Zu!-3G|TNe)? zU`eG0FnAb~Tzi1Ek4@@J7nh6=ka9v>W9nB}Zj8 zEoo$gB0>vcR~yA>QQLQb61Z5_`tE^6dzWyCZ4VmF-rk7jH}%Xt-ou-D3yt<^EvO^)4`VL<&`Ir*V`iK1IMP`>5S)2s?x^^YwPl9n8$;o zv9`W>t7PZLcy)R2aXyEpuY0908Ydl^x~2QmbaTE=4@f#^{BsVn$4&fwoUi99jwJ4b zVzdx_z3MRcW5YAwUH1@IgRao4Kf4nSr<1$iOjoe}zTo9>BbC9r+#j06{QP9}sZ`&o zFR;xRlpujK7epj;NAvBQ-%M373QDj&a(4r!lfx6>5BjDC8BpGnv_lnOXWU1H))XR{ zo=~3Vp)~(C5F>Elb1HP?0rVvSGOidn^S~Y~PHCqY;I}x!QFzcBv31}GEJjwpfIt5Z zoP|g;U_<>q@*>C|a?msm*#7*5JQ>lSll{N=L)^y5<>-q=(Z8(%v_OQ$D1{xv^XHHr zyty|8oMDmCa+;boBSQ_ z7U*?Y3aA8EHYmYvEWM9y25KK$BrfU3UYSWpO@ij_&6#5)!0)He9Rg+|e#Hu0u;)5U zx9H38>&$VR4+#k^>2DXe)(9*tNX-av=6cIo8gFC`6bS6iPU(Sq#hh02D zUIzqTXW&PP)X!K*u(Pp|eTkZL#gT=LH7hHW5`F(S(aa(%J&Dbr6{%f~Yx{VHepVhI z9tpCWJzfUfCyagN*pw-|{`5O;qVE397}zRvoX4gge*|*h*TgUWj2}rzgBgL1pak@+ z1n1>Tc=*$L2b9$$x;2GACvsXUaZCUFF<@ovu@8*k{Q97Alrg=KpB7ewMR`K|l8K^A zI(h|5pq|^nuUhyM^KpU?APaLxhHps2DX98Kd;*U#oS6eIF$RJ z_F(D^3HLf^dcP_0lTWHcjR9yB#myYER&h>F?1D`}ACdhudY%!}hwb&9z6^EqFSxII zFiI6@c~%&^%WdvdFMh;y=Ax^Z@tQBolr9WP-F3>%Gq4oM@jD+%hu*axD)A^=A}qDz zPq0FL?#MCigBgwIF?8VgZR;81fyEE|UMyk?9QQS1k**E=@;rLgZy)EZ{JjBS#df@2 zC9d^c;*T+Hip*ntuAR|DFlzGvTMPX&7%_YHL^oYG^A_}$e~kIO(_AO4={xbUut})F zypI0FfX2CKLhF>c1;v@dp%Avwkncdv##UVSuJ#ipH@6Fr?eBAp0L|}lGurZfY6_XY zm5%%z{bEH+i>@bxJ5PN`2bU9xQtDgs+V4eenA}f7M>L)q2cEZ*V`?~Tt>;5IqGYM} zz8QqpGMbVzx&8L5GRs&hQYH8VH+^se(oN5gc*BfCFem3>?@SBbhX?F-(=)sR}L#CKGmBm=rAIv$ZF0zl)aqa@Sl&+4hPo z_|fUh)p5MW5JK=mw3UdoDL0kTrL%2aO%<#H=y9FJA z9~Foy|1N(HCnI_zQ2wk=wVUVl5AOvIw`Q7>yN(x$Bu2e=n1O#jjCg&f#eJafIsa5P zy0c)-9h^p=Ke_qstfyew7CXP!SwtI2BF&v7YX---i9#b$sy#hR7qyiuDS$`rTkDUhLOVEy~858XJr&_|w*Ft_@?TGzz0c^j!Pc z1e4DBhUZ4YT3C2qGh6fe3ryHo7{gt?iy|2yU^>B2VuXe<^;m0J$Eiu)F~h7=usC+yN<+GxS~CP_vxI7cer?L{dfagEzI znJ$y_0w#Bm>k==Waz^EA-;Cv6wRhq5lPqdi13O&L#jLX$Q*qfePwpyy{&2TTNU`WC zmR4@G%%gVr)ZH$dkup&=7OwxWk3zY_U9!G67wXpJoEolNAs$m@7u65IM<c!<6KONzbH>{^H{Rhu55q;daWtt&L<*9{`3c+Hd0x%3zeC`&Vs~77ZTFmB5R!;_w&vGhgO2bNTf`77S8(>$zlqEeu&a z9itZ_cnToK%+^1^rdn~#x(OB?sNvD$H8SX>&-1mF^dz`t-d#N>Da5;?-K7nN3azOC zo!hTc%GTdEx)f+Se*hGoL;Kq1;; zc?iKZiAVk5qb0_>ZyPACuCB%f3uwpRbo$xo_(~*$3pMRee&=IIaOuiLHr*d?;UKtE zTblmNkN&Mvy0c0D>=rd@XNLB4TUdVGjCrUH68@|iYc>}3#o0r4Ve_-~z#-q3XD9T+ z=tYC_n@Ps^QiT* z^OL=O7JrHLov|rk8-1hx;D0i}A;5s~^&=}FQ|EhX_;lFXy6Ogdcg|u^N{Q@6zQ+>D zGY(-zR_HcWv*fyMj&tKYn@W;19C!$`cYqBmVU%A*YEvs4+Rf0Ksx$4C84$~g!(B@+ z%B(dG-DnXqkjfZF(w1Kve1>OfIDX|Ktve60&YmP*Th~g5 zCnI2)SBRfN>fw1t#N1Q{JS(tzBUe3@^cO2hxL=uV-hRTEahq1CQTB!HW~|D2U*jnF zuHUy&>RF#ptyzl${cIOGL_(@TH5S1^ppurHDByt<6kc=A_H>3x^2&CHWVwkLav0HQ zOWz{h-SkgXx0HG5HNg5})HO6jkn|QN$qo-X@8cEP7eOr_sXia=g_7&>BeCIMPPrT{ z85J$f%fKBoYdn!%X9UCz&E6S8YU-{5W`>-a;g#PctAudw-Uft?=rW1 z%Y#rxRAZTs@t1Y968*uNbCb z{UE)Rv1BMggQ&xb4Ak#EG4nDXP{4%|5&eaHR_C;TeJLiFs{zVKIahs~vUh7V?|ps$ z{^<(!etn^6kVd%($s0(n{?qAYL6J4fj3qLB^VIYYq*-yu?bT*|07y`?4xt)J(IKDNpsvMhkO;&SMK^`kV(OV#Q&1I=-Fjq5qO(c3nmFit8M8Plh&u9{3ZF~O# zH?rPS-=t9PaaN-Cp^oh__FJ$$#k3Gpj>S`v6tS=wjDOd+NJk3^IZHanGTWkoBG@qP znsHC_`hjsuD@7@H+sPL_j{&)p_Oh@kYl`g@?+SY1TrrjD7UV z=!RLc8k+;Wb<7T7(u07N;KN@Q)6Ks>QXW*Z-~hkkVHTnddAN;T*OHaMEhUML!>BjpWLx;-w{oPpc$$SCM?+c?o$n^Kss#`lizSbolBjuSto7rW| zH_53hEs?^F%rI4ip)Gq}7fBwL<<^KSVTd6vgwt>S)WA-HO~^c4wjR+ zd=6DV>o*}a^8^t8`Di~+To@)G`}l&8)^Xu$uPaWK84O0#K%$9 z5urh!@2@#s!k=S>%0CujH(AsE_7a+C>wzS*U4xHQ-GfjuRQEJda&arYTn!3;ViOGV zD6V?`t%hIpL+HQZqQ_BvXFX@B+1L^EWfU~ajxge*l2zN)WB_UV0um1#cy>RTFZM8A zKmRkuFS*=G!FdaJV4)=>SFTa0tgCQxKyv%p=5397ffA5s{~RGicNEB}!STBrkKq;>75M;)}u_^pZN5 zSqRmvmi2qHeJtq$Zp7d>!D+J4QYX)Jx zyl8tsK!Yowf3t-=ZJ^JJ=18PqFRj+*xA*txc=TzrzpA`n!McL9Y1$9?CO2&1d3FLg zM(LqtRcD;6Cyv`9onAQjO{e?6lIb7=!oW^CTnvWK{lgD@5zXfB&bP;E9u78Zt`8d1 zB>IrbN(9URsgaQ)$b zJPJ9RK8FEJaK)*bgSfd}sU{ zUYsPtyl5L{jMpV;4W=d+fs%78E=^XVP)94!qVjm!X@DziT}-KxWH_s#3-^4lZa z+oyW511Mw@6qjB9;w9#!i{6?VPr@ojD@1(?vu1Fj5jrB(Mmdnd%6LSQZa@*_3c%mb zjg<;I|0eo5zPGko0rfy>s=pS%ChZjviNkUxC1|7-?x*dx*mlVEOG0!`#idswUZ$co zr(d~yCvezioOl7j=rL}%U|wT}@d&>O`hf0AsJPKF*~h4b&hBIwfq}(rKGzp%lXRM3 zs%SLhFo~rr_H3aUArwk=pgaKetC&Qq4;bo$7Uv3pqDq-bb$)C^utZ!$@@s01q8mzH zO`kVZTX;+1G8tBDw{=ywH&U;^oM+3~+m7k0qMExKO^8;~;&9npq_3n)8!Rlpv2!jde)Fzo7RQi=oc7I{nF+f|;Tt)=YOcJ72Ig#iL z;tskV8F8Xrn6(C{#>whwQydxy_K}xGD36tVxqhx9yb+6>n4gTkSl?ItyscS?Cy#j@ z$a})P5{P9Mmpu&UIJOHSV-i}^k2sbwV5AJm%LCzd-YSylhJaK{rm$XTvS;fXvH z+oNeV{NwcfrgxCLjEd%z=M#nH0L5CYfLv_Yq!8xqTg$pJ18u)kTXBO}8?Hylt(KN> zeb+)*Qp8ZR+^w^(widbO5$>n_Wh1&x_SxQMu+M_W~M5Dcg7= z(6==+L({#>IlHrkjI#t&>YGJ5R@_B59@zLFd~5c;42Pt(<|3|2(xaeJSFo*^2%U@$hV5-=Wsx*0H(QSwGuc8T9D`D*PIz72og-?dbzX$6x*Y z->C>ia*pjMxAFeNR}?g*BHt+G=b9&RHmE(Ml?B8Go}R4lfVMw!wzL_y49lhWJ=vLG z!r+`9^!*Gt7UC?nUU{V;T$0f@7m@?Lh>qIc4XL7E{dCYCb9Tj(^DZ_|S@qWsCa&S^ z5^$loAARmhO|vicnaF?ppiEtB^mvZF4@@kkI8g>UdmfMstTxMAS1)!i{|+HSP9Z7G zavNeope1f!_@1d5c=%_oV^uIfw-u3DYrC*s(KhG=uz!MHl6=a6{>dd2qcpT1bd*fj9#RyCfE%i+gCr&Qti+BG_wRM&pQ0sB)DY|$q zUw*t6y7Uupdti@FQj4t6ug9E}B4gwvBTM;!5n$pMlvA93U)J?o!eQiqzsMA!P)NT*g^QullT0$GhREQ<6s?vU$k7TVD#QT@7zKKjB8QM z)rmcdO%Ws+4)>$OppYc8%dyMVi%u8f%z!q`RvjI8QvzM*cAS(XDT>(W?p*mGYlVgy zWl2?ezixCnQ7_Dn8KsSbYZ%mxETk7a-SbL1T4tD z>HQtazuDPp%BMmk6CR8>q1NRrB!m>{XW?G;E52u4!tAy3o#?$tU~WJslID5Lhr1t! zIy4-I?fMt@yN%^VL^tc&aywThuUm7CzJRUsXfT7P`NXgGx1LrC4(U$dBSmD=W?bJE ziSLCpO_*HqinIFqaNOpXosDbi4gdhfw>f*(ZwZRuu->AlPKym0Akv9D9T=_NH&@ZM zym>7sxd16mo>z7GVa(Mi4h=fAyKKB77>nHxmQjc}E1AWwXjM|reAw>o^%HbG!UVQ< zBcv{G1~mpy>*~Wf{7&0{NRs|y`yP@#5LxaIASI4qz&ZnY<31hhXGm6W5hcA6kHic) zqP3cM2jk5y5tZk1X8a41C5D7LzTxUSAkc%E!731QT~luRxH~n`xE^mslXub@Njpb0_pJn894q$ZkEZXbIl&?S;L+qQyLu zh>LzHE1h=X{RPy=*iZkc968PNx@Dgw(B^sDo2l|J(TT~5MDG*SQ$jZ+2CS1|Gi`xI<0#c) zFmcTJPOphkd!C0jd~V;yY+!`H4}tYm)?j*!D-+DTFmH(E9R1109nu|@SZqC!Bi(of zrBD1(^rNRbG4WyCJQfaoCBix{NQ`=C2fB}78 z$tNFAPC)AYq{~ii2m&8f3lkM+?j=~zWsihctIc8uGFfW#b5Z48b#o^9?o{n-{1|ey z|MzI?`uY2G5y|JK(r<%Z3Qbzu7P&F)!}p-+BQj*}igqi7a-p6FF9MkZWk>!jH3A~vDm)390Ejh?dZ{tSBkZl`EO?Dnw+0-~9K z^X_@@+dT4J=`vce^;f)>wUbL*984GiH}H zCWzB_3h#g&^jHY5J9iW|HS7^gwD_m747me9+U1JX;HW{tzhGRdAr)+$iU~Ro9(H~# z;Mh6M+)lcSeYhQ|7b9v}A5d)Rz@1&B9PC$QBM09Plzx1kS&}kYvTE&W*S;&&AEW$M zQH2S0BOabI9|N%p_B8P9d^pEuLVja>(vD6WnHv!Wf-F?M zCScx5`@O}6PjpOA!v-oQR4^*JSN$6s8&J9j=k#=gi+BMi!vm^snMrjq|K**WZyCC7 zxKS5%51Z^}l!^bPCI3c=j2qIv)cB~sO|%oRvRlr62dFyT`nULVs}sxpv+i$%$aog` z^dF*8ahbNMp~)LG0sV(Rx_V_GRN}_ErTfp86vZ1;ON-$?0g5L1e)&oibF03Dlbhcg^e?CS(-^)8Navqh{`YjBkc|vu|GSLLWcGjT_WybO|K1=}Wy`Jvgm0w9 zC#{6Hx~qI};V_1$L~9U7)Ya1`0r)!_7~6Cx?IcQvWqFpI%lDyHX>?&cr5+u z6!XEDQ1P?QcC*qps~T*7MzTycs#PCLeMd~<_Vl{V8pbCnV8#zB>xq=!iPgpwHs&SL zE6|%YOKZXn{v3JJrN+}$^0OlK=mT^pK3YZbdrl4|luG=2VKChqbIT>j?JxDi$hR!y z8mX}_9;Pff@juBpahZj) z$KsbYmU|NUMvtJJ{{)9O{0GM@U-8RF=})e8oF5pc5=IEk_eu_=|Dg;aW11GmY)(^|>%}9-dn;CVEq={=hahIh+oMZI_9)6#5o4OaWwKY0LjCbX6Wk&qZd!b7*@ws^Lag)hsPS;e5RO@#8S zx~r0`xHQ~SaXMVzB0g!>B(QD|>u@;1kZHgv-o95%sbyu_lD@C##M-9Hiiroe_3GO8 z7&8p7r$z!Jt)^lziXcnF*%%BKn3+0d3&_>%23;>!I6*S+{NV4pXFy-bw^soGjysrw&i9G_7*Yw(NHcgBjU`f&2-5JhTM9c>v=+pYw@L6 z?VrNmZ|`60t^o;yGXuE*_!$uiOYUi8A0PV1Tl2ElA3-n?O4@lY^a_MsczFxIXG+T8 zhP*s`$Bi8!73p-Ewgi-6@AJx<=?ZYaLXOZqUrk{90<<-=L(KS93q-$M%2E=HFo&Fe`0k3d3H}q)&0fC$;r?1hs=w=pvR3nK` z%VaDxiNsRHiI;eIxJjmF-$w3z#_-!*sx|1&CiO&9wG}c)KfIRY=;Dm~h3$ZyeHI_Iq!DHi8D>?@lulH(Ch^nYi54Zk%Hfd0i(hdEH;bl4Cb&%C7< zKUYI*xfV$oUykw}2|WeGvoqq&CQsL+a=s9RK{_F$K$Pq?Y~0kiP+v;(yDFrF<4De5ehBYt zzhMR8Zh^KV@a}_g$oub9HW@rv*1kp$D z6T*^`5{u_}3CW7#XMkDY=tgpl-|!d0uJf(Q>~;v~e!X<}6v2Yd!bVOX+Tg+RDy-&y zXyh=LR3>0)ey2Y^i4w7uAiyK_;jK>Bd-0Ax0fmY0BzQ42Z3-!?_!* zw31Cv+^8SvLUvGC)=G}G5Ig+iLgjM3nZj&}Lby7a?&dEQ#Cy~G4e*jSKZ+#ulQ(xp zBO=C60J@L)M@A)&V?XlZawn27^PWV}^b7Z{Y7*TL1p3wj_Haa%-n@vhYE@sX(W#!f zerH5352FniXB*T!0pGP?%K42kA70L*19wKn185eN?riWruwlxkYAH>xM=EW6l3j=3 zb)N`fY$B6TH_FEv^ITZ!5FM6-T%2C3mpo1|rDxya9kd+^nlg%)6^n4_XYPa>fjzfA znF`{5HMHXnHMnNCv3$lQVqcRo?ZACp(3*BU)V(RUn=mevU5ZqOTt-L)6>9YON&B^D z98MRL{&mV3Yz)UyoF^>=78*lf0p<1T+Gr*1>I=*?xDj^D_h&HU9siyEa%2)# z0gZKl{^#|TT52KWWS+_XsSW<&472k&gcfx_OkZOJDC-LTnjsgAodzQ4sd}|1Wg_6Z z+T?Qhqls*dr>%BAO&b zhexlaiM8)cd^b3LK*|qJSh&UmOYTGClrXwoT9NtSE-4WMBatMDjhM*joV@kAJxBx4 ztja3^Ntt|dJU68BZ{!kpwb_2#C|r}-XkWc^`W2nkV$9H8*|l^1rFjL(7UE0x#!}Us zH!zG{x2}z9ZNruC-?5S6jFG4pqPPcGM&%aU?n9-5^rjZ1DG6@XU;*K)a-R{D_dvw3 z?j)GN#48YQwYt;wQZ%F4Hdt#o2-4ppN6ST31#ZvGGm%kv@ksI%3vKTtv7c}+p>jI_ z441fyJg&*jsb7F2e(QQ~i3j1$adL6Xv1U$E{1UJB@>l~>hHKo@J$Mg$+(>E>xdFTO z2m@dQM4CE^=Dq@!KXH}WdHCo2D3R)$=S#clm(e7x#W!hknLa&tZQvGteX<*W62Yn5 zujniNJyh-S^WpJvCw|>Gk7M4#gFYxW79%J)=s|2v zo+X5`ZWMg680A!Zkp5Oqw^9@riz=+Y;2AKUC6-jFg7MyDE!csGxAbXQc0B7vNO)On zIFZVKkfQ5eBeGXuhG3L?p=g6ei5<>mFf?4q@pt)p) ztE=e{PGd4YC}1+xyX*J`@Ngc#8!VFk*AYFUT z5nX$!3Cnz+^PPm}LxGMmsN%Z3@ng&LHI^W`9zn2`f9xQdwW;i)PkMfKQlSH>V4)eG zMUi+{d_;^qJyu_=HM8JiH7tu7DdnktOd|t<4W~I~SGokusq(qm!IgR z!=?SXIqTCkeU@#>%~!PvxgYz5eHxVt;&Bh-p~(J+9mT#fE}OTt(RA#|< z#rukktkkQaU68b^`nv(hCGhw3W*vZwNe2h_(zv$0`>AOy)Ys2t*Ap4verd>%%7aDU z;(VUkpHx7FHgj=FHHsy^A7a@-^rmJL@x*dn^*me@H8|XlKv$~;S=*SVg_IA&>Eikt zO=R$K0WPQqh6d{VtPyDG=(Z1ck>3=K1A~LoAChQ29+DPBo0quUh{KRESz zwqanC;)f*=Z6n9e(k3HNu^T#*Dccjqtd8hl1D*t53s_k-H^k$0`jd+mhs}xhBe8pAM?#L zEXo3BhR~<5C}bDJJMp#J1ERhtgY!Itn=uSYmpC^+W7T8WP5E8|9U za!NNU7!Y~6eg*%#6BXJ3jK! zpXX|+yQlr3mpwtejDlgODN~6!F|(BI5WMRPxt7Jx@=@teW5-afmxptw;34QFr*no@ zpM)zN_IKGj%vESp+=`(0lo;FpG!kq0rj5jBCm=HwSZP)Xi1XcE_J8DbQ<%`7SFI$> z6wgCg9sPA-zk!Rf+*GxhFCkveDm~C?Jxx)@8dO`3b-Z{LR$@)Sd$K@vN`Vi!q-Hko zGbpITG6*O2nC>`GME^}IKi#OHI9HRB3cz~epw9 zWa;0(!7O_7a0H#d3(Y{xHM_^*sqGG=J(b`1i0e501wMIE){8<&DT{>i0^`{RKHgs} zro(Ge@WbTtmBCJpVqA>;*>F~F53UdN&azUA@GMvEikFC&%QHOZ;Ce~=P-;|(c+6)P z#jMAYo-{ywS5@U~S=^C?fbL*d;3C8a%PuyXZPC}2H04)Feft|J6_{}aOQ zHx%RmR}x=;@hF=_BvRiFe@J^%%_;Mu_4HIH^}q9d^#bl-0i7jhd1M_s-Dyj?iN5Bt za-<6E@E&3k-sPa?pirAub-45&28hu}`+6eTG8w|Pm!IH=OK4>o^HItaQ^vR&%Fgsn zYf(lL6lE2^Sm$T4X^aFlN*C|S2;2)cB$G8|`^E)0Azjb5c>nnO6>3)i!h3joyMF85 zE$h)ToA4Ubhc6cL|*+2hJ^N(oidz?wcYeGGmk(-WSutV)eZnUP(4f_x5R`F$A~BaO@%E z?72mLtrbFRxs%*YIwbGh@m81JQG*|=Ueq?-mD~8doui;Ex4n;tzApSN08&z=5+#`jhpQ(V7PSzpNmhYs_zx6Fz$1?A$B1*`+ z8z<9qhcq_QtSY)F;$c!JqzUz)bH5+C5-*U9&&`QiiXnlR8LHnuCe+XTtSJ)S)0(8l;(QaNUQ zhv`EYMpRx7q~G5&Qj3HAv-q zef*1{i9TKyQb)mh0mDo>fC1@8T^sGo@Cdi|%(ZLuwa(^lut}suk*KfU@X&*%X<)os zIX-JvIV8tEGz!74s>af7%1CzuIbNkdFtge{KPwhA0x&ubKa9`n%?}iiO9S zS~Pb&aotV?;_ZF?`D0|H;rREmbf(SxK|jJXA+H%ee|>&)u`*gx@|Uyh;x&_asFR<*rbO>X6Md^GJwyW_+KM~JjZ?I(q*EM=TwokLO?_wgXP$M z*Z00*+@p`nDHi8RT(m@qIpPvV*{wKk>@pXw9IVq zsZ|VlhS5V?9DF?+ifD9mRPBtzp1Q5(2p<*&I1G8lVomnj6MDL&>{`bBT#j9szxE1T z$m+o;cTQ|L`nkFtg_58VZe<=lm(cb0&y zu-T!t;yXXoA<1xnOVrw-U24!}+;uH_Us4-2S!zf?TWum)`jMjHiW7IJ z6QK<5w-5}@eGWC)-GLYY`UVU+kDt;^#DUC}X7hw;iBgWxGkutB--pYipI$qtI|7rya{d1LA6MR&>Dv>ylh zk(T4&Rpoon)o^bNnd!P`qoXrLp*VeNIO{&m@@!M6rCVn()_7*-G>WIp{po&~-EScp zQ#l|zr;PE%ILHDXr)^3Df8=;}G_+$xzBC-t{vh9L$E9h@PCV&9Dz4C`0$ z-JhhtT7u7vm{|R@*hvMuN}jPD6nYmi7EWd0nT1;b*r#a<61w%%iSsp!ER`!eQ-Fqx za^m-{ANV-vQ0TrV!${=P*GiAZFy;|sAflMw~Zyh8~9e8D>Gj$ z{L>$nqa1NJ#MS2W@5PM>=H})QnTfq4)Gp_#LW=^kZ0bdrC|3t}YNhO4fBVJl{qTBp0O+YWU@KY6?&h0Kwt^{k|DP4&h>lPetU?+h zkvzTlHctOmxG{e6p22pki>()rte1OOX;eR18Q7eS>p{5JrxsTLPm1GZxbgaijm8%$ zTsIv}PPM+*9x1~cv@NGJO8iV07v6;g=$D-VEeTN!^noO#`%6(2&N|+}9AhbPvD`7J z9+2m(P%g}`Cze<-nQ>o=Ranw(zMLY{0*voGJJZT)CqPL~$MR{eS6J%eTXNm~0EIek zUF^?8So&Znd>4cCYTc6w$9sD5ngD?TuR_tjDsY!OgDkT99+pACh;hH^l3+O6dye4@ zu>;+90P?2q3-Xw57(d383RS-xAutySaVya2ojD(FTDlUAzsxGH^AmC<1+B|&Dw<;D z3JOMu36CtH_~G&>>P)!yc6;Z^GZeb*drcmfkxY(p|kbW z&0b?E-qQ&ta^_>a&j-_{wP*%4-f_LWT#KGPtoIhr3gC=9Q{d_Klo-Gfi>^iHPSW>Q zYO(1OX`K1fMdDN_e;4d#X`vcr?(Ffr4f~&#OjZ^M!)s`rI8ByKc!?fQDHgKXNhavF zrNgQR!E>}JFMPd7amFrB{F(KqJ4~Z73#Ee`J&{#|Ryki9!9e3MnqJqP5gX(s+FKA@ zjg3tsW8Q|?>%u)y#GF_)eiGVe&GwsyhB*cSh%lE?F+G8Bai(MZbxNnkfd}#Vx~0II zbZkif)XXRcMH%h8su7+IaiQYN;@mP;=7V%T9BGLHp`4htNpqZiSF?pnc*Mh1P!?Nlir za9$WxK*cgF?l-mjzC_75sV=fq_Bvd1Aq?*{Y!3p2#c3=o=zj0e844%EeeCs0nkJ&EtN+h<{TmGiccD}pk;cl zk912;02pGv{u5c>0(f9IF48a1FVuHt-10Zq*W)#=xd0rjeaq?uAPB%}IXj8KYlQO! zbyE6PcCmGc-D10f;4vx1B6+OYx4y*CjA}W4Pl+9+d%p9xUwt5o%My*gUNn|8tYneL zazM0}L5VTks4@PFzqZ;)p%c??24GMjwnk*fLC6>jL%NA!j$fRrqP9#aju2 zEjhkb!wGBw03_nFI^z!Xoq(dA+&(&dpn#(3Ur0OSY7%L@;GiL>a_@XZs|Wr8sAIaT zQeb@Pv;MMDmY6G5m~wkwS)rnUSQoc&LnZtfrY*@B=T3>+`l0Q>hESMWZ4Q*1wNiB3 z;Vnf*$*U#U3(&KTn!p#|zs$ zMc$jJao}>~^KRGE_~P3NzW7P~6V-a?sqf2RWc`85Lt>0Wk{R*(2Hf9>j@1t;=BU1r zRB@Xc1tSqOHv4(iPu!73HPtik9Fd1Ad4`>19Qu_6;IN%e0uen7_12YK8=0Jzl3DWB zqi!B7+dzaciE;1VRa||PmC_`r%7qdQPZ{>@`O;vw3doAJBWH~@VZ0|iE6wwZv}1_h z-VH6ki06`O{MES4NFcR2gz{;j>8w~wu6z3way~9H^9wY%T-ZYQEy9t_sAprx!`xzN z_1E@DvPKJgb!$`0%3Rmfm*`$F-J7vgYSY z=D~N4u@XZGW=3jbQ6et*7o7oAj%So_6yf%Lboo!7!H=)RgfWe(wdRgR@vhoKHGDkZ z6E)+zFG#)S-Ok+2l`OEZo~|Ij8YJ z*sH?}H5Fy^jAqmev|Kv`!U7l42Vq)o@P~joo@VJL`8=CC4&X`jOHGH%Lzo2ZdxDwA z`pY!PM*{Kt-Cxz!SX8+yE$$DffB(+rtJz%)5+!XPZNs3UxoQ5^M0v|DW~nC$Z)ax* zV^88GsPbYTv{;9%*ncEVa0y*PQH3@pSIkXI z+!vgH(b^~ijHlenGVu&R2B`2ie}XGT;xeO_EwJkm3qFKF#@1}u^;eoiya*`9lD#mx z!G44_hDF_c>-1|R#_Xe{$`5a#Q+n+M*ohMe;cTh%nPlhXMVD|`j|xTGzwWo%C&YHp z6_jNmu#}+WHCUOH%U@6^p>bQ5Zx}vLLfnzAe9#prz;#FZ@Ka5n9=A^#r}_`rEjrIh z4|7uc?;@$~$Sm#UvFm53T39}Kzc3bK@Jw2*Yv6o#-~XM1Ms&l4WXM>f;>9zP!ClFA z6205>h}vRswQ{_)>R09`nIWwGJgr|+Ok82S)gS2igMy>!>T;X@5fWfai?f!MF##^2 zLa=XxWi~!7;wRzzC`y~9mNL$tcwRVrJn^^}qRbd?95P`kA17bJ#bTZ9t{IHZS(W0$ zR^R>aO_i-_OOw*u&(z$UA-c3D!>(dmpGah{@ZFt`f;pZV*^=_x86jJK573Ve>J?`# z*Fm~V!i7GSZP05JxS_(yphjZjBQayYs`rdC7mGSPmpVn9SmA1S{@3C7r|HW#t1TDJE4$-=q!Dk=tAmdnpdrEhUrEKAdHr7_{eQmFNBnPB z`~QzODE|DJmPe5D?_kY*JG6H=%>VuxsBERLub5Owh=N zkN7_pe^e%Mc1+h+^ql05e9J(VV8!>NZfU;b34X#%dduMKB(;0**r~3{Ia>ng^I8AU z5GG+tN}r*3VUsHV*J`gX^6Lk0c@&zMKN&Ehvjb-T)tJ8hUHHYUKdyw6;4BPrLIeQ1T5rHPXyY|$*ybncg%mG2yS#R5{BRCWJH z{=x*G{0RjPPUgjXD9%T|Wt4c*NRTu(EP&OH-M=%9!xBSha~TX(UZu5ovfRQXNgdnk zQ+;`{bI7mop>oKt`Jcw1j=c8JLGCy#W>F&c^aVKd#cxRP%iWP>8Tm61b`I-Y#{d39 zTwHd-foO5#*FT+Xf+YEA{bH`y*5j#M;ua#^BLQV>Klgsn+&69E>liSy{+q4gpZg5r zUyT!86d1yC6WOoWJz<$W{d16GtUdZ74riL2^NzvJP4^=&Co<-Mgx}+VkkdC-5|13U zy701?zL%r}AatzW;Q$KNS&{z6bY&f2e%svLBf)ll^pG4QJjJ-YDk*RFI^rh&vKMND z7Ap5&u}^~ZpPAsH=Ws9=Ue3W8%%0bA=r_ya(s|nx`&AN3Ppg{RrVwFzgvS$}jKgSC z7NxJV!bjo;l+|n#p-DJ(+;Ccy^dMEx$*PbsyyNM$kI@mU{vSF=(BH}f#jh+m_oA&){1j#{0?s0gY{S-j_+J0}alm%t zO`cX*pVU~B?R(BXPxF4NOFGwvOt(P2bVw^Q3w4ux;+SdHr7XGMhHMx=1oL_|xOidTS%*J{QbhvA|P zX(Q+2#dk3|UF54%ostS^Vjj#>US@3~uuJgkC3y=F8Q=K<;gu>cXK-ZRfqbUgk{?QN36fPUox5*kBK1Bw|Bba43+m!DA zvk246-D7A%WqU`e!#bLrS%;V;gkYku`&x z6i#AZ`TSwoX8iexmKMM7sVrGh=N-zhbv~6qb~1`@Fb&#f{D>HmX`@qHjWOw;phmVr!nJr zd(;1JPG2QXey&mkRMuqQob*@URwehj0!PsyymmcE{h9$1qLE56t;U^d-?rYBYBG0e zQqEDuiTQ4Ow-IWqGodllE*+J-xcB`OP1RdLW9YujlBTj{|6`};-H5Op4HA4y;@k-1 zr#dT|+mx?745DzW1(;wn-#p@89|T0^IC9ilUjk3i6E3eycPO_vShz9*#G{pSLnFo3 zuzlRwQm7`EMeG;sxl=0jg83@O&$iwXf_W~-B8B4Tc@{xmZQ0P%#Iex!mF2vK8AUr@ zqe2fV_AbE5mCo){^AWf0QAi&*PHxdICi<2k9py;qiD5{q`(_VZLZq<|h+~8*atgB| z5RXg3wJ#%j93*372|~t2SadRkT3Xy+_Z=NOR5iJ*Yh5Ql7~%@_A1t5P5$>og4Y6*yT(1Qd{Os#YMg+;x&%GPBPeN$IyaB7RA71t4pSs&p}AXCPY7F znX>=GH`6k9HueCY9so{JOKZxL*Iz<=-$SXzLR>$hcWuRyF|fMi_a1leadH3>PgY%nJ$p<)H-(nAl!NHP z^y$pW?MzeBzRseGlT*W7 zHO%3tK#G>0IKPII^UMb!6S5Mrsr>);hktyBau>(We}X;7TeDrygznSS+(B+}EE9t( zov^S~YdsTNf^#{y1SezyKsI-4{HG7GYIZ~JYjK~$4Cw+b=%?OVuFn{FmEPj%C@8hY zVcA(~qlxX%I4j^OK@LKv=n#3#XHPvs%uy>7`+Hxt>q;Rc3**{bw>byuUWxBHX(eg< zW+q+}Ks7k?8g^zGxjY#^3E2XFt1a9RUnc zZ6tjGD}ZJ0J z4b3wX*(G1cY;znIeZurzzyvPD`5KErip$&|JaM)>uYn4GaD)yOYYiGN?80My$s5tUU7-OW&=#l<( zUT@R8J~S>h;E#@?t$EPY8za!>0C(0;<*Kz9dlBcqKutDFDvjfFyXAF=f7NrIcmD>P07jTjo&u3w1;f5PQ8Q}?}p%0wUSNwiTOGk9%)_!GTX z7^mv+Y!C-IJAh$eIDfe`G9o^9?;tTVBk!?B%A2EFlfdZtpwlSibntDIcD1TSG}^Kq z)S+yU(AFeNr$hj~dx`%3W{nE%GO}z@#N9e4Ly#K+c)ve;Vvwo^S}uKTacT4TbE(hH zU{!&|0z4k)ugDCi8bNZXT)_TPwJ-UHqC;_{iGA6afxj*cpQ+pH{4Z9a1q7JsoN|&RO+c$h-B8#Eg@@L8qopozM$5l&v zx-%i)IfC`O-KJ_sk?v)KMuajXpEz5L_L^W_PCGtN%FYO~W+%|lAl}mbwTj>kEd?nk z<8XeG((FmwY&PGnCE%45)6p=ro0fb!U%`X8{^AdX{6x3Fy(oz1x_mr{Ng}(GNFt5T zNXMP#2U?zOBYc&EM3B;o78KHN(&Bs$b7mqQR_H&nMh4#nNwp-6CwyOrWzN^wcC;10zdQrukv6oNDPzV~}?&CFV}=I>

s*X;yPy?<%Uaxk*V(B*48q`Q0{D-K>0RfQ{UQbx;1#j_mqh9nV%l< z>b32v8KG%>to#H*bwr(S~&@{JdJ{ND*2^fb&qr??QiN8#L{%U07XolqgmcRR^0^UpubE0j5?)yis&+Lqb zoY4E%1q+-#VXJLDPkdBO_8|&akwqy-AA7CtAN+u2;d z_Ft&(j>QPx9+`dp{!edg8!KM=dnV2h*029&Gh8y1s!>Q~B>6)(QllO|*yo_i2 zd}_?Ww3*dYD%7cOg$Jb98;g3c!SpP8izVi;s18>!!TQB&r|E8cN~o71^!j*@FU&d- zjrmxyh7~U|s|ESLrSJC61?|C72O+@lb5XOh0GT$bmcD+Rf6a2wK1B=p!;H&fjW{+L z84G$xR$LtS8%#1P^fU{}RgcC3kSO@opy+-mJ}kEwU}({KpoHOe+ihyMSi~*PDozQf zt>e+Y)Cm+k03S*?!1TzU|-7m%?|ws-nJKVCTMh(U(l(R?p2?QpP>Zasob#_0i!$ zB@A@8g97pCPEFm_@PGhRX9?oZuaAQTV&!m{HdLvS4RobDZVHNm9~3zrx>e=(mR~(k zzUYlP7jgXeU@X5sk-G)#<@OW2D;&7_(XzjSDMHwNOYTb@U>(W2nbJ;a6zIWqB!(nD z26Oq0)OvS&xbo7nF#zvMYz{Uu+s*%E70;!FAK;O?0<*q40U{*+drXBB<8WD6Sk$Zi zR8|E$B)@DuR{}Jv>RxQaD^G;)$bCRIhrD7s?yFBGFyj5lV@U&(sbA}G0} zI^svS2Vx7qh=lp~D118B@9sco#)M0xeRY-t<87ar2cBNa2&6Nk)Q)IV&o2`GwA%C& zQ#ed&p5<$o**n^TvAR>v}ykmy-WFyL~UuZf1fwOt3C$9eEa0J2Or#^nb_pH?TylN zY{a6R^Yo8wQn&_``r02f4QCOyn(V0HzuCne@6_~u=Wp-Sg!!1wy0hy|Jk%L=w(Bata{?l~wjH{`PFAkZ(AkYbT~xno+`~irUcF1|_vZ!(jmLBEBGF`> zH~X~bnm%Ept^JUemXql%2|)h6%Vm!4Yp9h0SNkkX6p3-|T1uQt>Kgc-U&8_!fqL$< z1O!%p=rj<+ZNsfOLFgoXA#X5!gyXuw&kOw1G*1_< zw+_y)#Y_Y+obxUZ1T~n8aE_&VYqQ_D+Y*@dPLiM-H=~|9dz9EXlRO6JC%T^VcR%8X zZ93D1UhYz6^6jG?u^J@w;J4tF%g%v(Z!Kz(Y@9RW5p_Y)TIML69{1~Y)&(z>_df%= zV)=F%(vwW1c6yHM4roaU^w&S$V3RVkhL~>O>2X)#qU)2FtQaQ^S0YYvU2$8L%Jz48 zaBK%~SLrR`C$@yPaM@A*oD_PSly%Gjio_x9O9$GrGSnn?Gcsos`U`f19_!_VSFS7f zs>1H{guyhQYY|{1Y1zWkns(xsj1UoD9G8XcFv=kva|vTWqXrVFQ~JPGvF8;3U7b+X zyY!kzbbOQblYeFw8==7Rhrnh5x^|xkuy{9eJKk{aROz$P)qNWX20E^H8 zamBCJYvn{~6lD%O;bBTr{hx-HP?{6Q>(U}04YrdhoQEZlnA#t}BL+Wr@NozFb zS#R?F(TpnPbuUEjAn}l_;N1SP)l!bQv_Jl;SJo42+?ieH=s|66Sj+5da`HxB>;As5 z$K0C(x&Zi`BKAu<@sgxTkmfp$1p^ahA6EPU08Zkq2Ubs3GrAjH4(zY zn!`v8dVAJT=B{O(tY8xTl1NKotR zB)25agR7D9diap5!3T;`q06@yd@y_qit?ZO+`KvUt7%Bq=2>D3j&yRjguJ-6Pni|i zTRyjxBp~0Y90IUV9L@J&QGg}fathTSCjE!~ab>o808!;7faY5!DXkQiouCNv@@sWn zcX9;nuKrkcUh@wc)PD=IGM{b3IV`;g?f78+@s(e%fy(61?0d>Dqj6c-%k}g+|7nltPGtqpsl1pxnXdiN6+4DcQo|81|MCw@6+0Ij|3AJOO9y!ocwZ$SU zgr@XO?v?1OM9`INVUbGB*``HNcfGSF=Zh?Pz|*RmkAi;3SwY0%5VPebP|E!C&bXI| z{)6LsdxmdskMBh~PvO z-6sSrr0!Vc`DLg5HmNDjxeA9`z?>0e&o8b8p{a6Wb^ELT;EM$Ab6=FZ3&BD@yLfaD zQ>uZT;VgjhOjPPP{krbQ`NI=}tm%gV{6FMl7$%8whX{{gzC9IC^$O{Slw=L%0m-XJ z_Lpv@zShiNH-I_*{pTCUB4u!VX^lE|)u&G6U@_0ZI&F`s2{GHL`Tl~w$G3*mc@1x`NV6}u8x$7nta`EJiR%dB zgsuMma7?-ROUYvB_v*6A)ZFBy;`gdVtqM4vK9yfW%!idAz$yoSq>%}_-hu8|yHqH} z2&7vVPnr!nEaSA}`|0TxAyKo7ha$6qshkHSzwR^%E21a|L&pgrE~4bej5=W^2wqM% zpOtXJfCLFFBx{KM04Vhh-1-c7) zAmdD-y}gv7uI_5uF7wfpPjlJrB$^~vPX~zFJZ!Ee;TWARL?Absr5&*!ADQK#!{;D7 zf7ByogJ^Y(s?X0p@R=xOCf44ktG}h11U9AEL_pIbdix$^&X*+jt{sPDs?Bd zr+Ps*T=|1X>FP#`%lGY-b>VoqzPGqTfdvQjgZjb#ib

#-VK%k$Toanc{6x#ktW~&osJ2$jhmK#*3b4vItDfeWo=pGK&R2HG2sHNH{&M{z zOc%Q7=pSHF`uUF-5xGepX#fQg(FKrf+;U1wxk`3YxQyYTI@_ORV%t>WW%5y#I;=}h zyyn#WTgobm+%+7!3Y>`O{rZ;l?LQrlhp0Dlm3F zx5c_6c%tVcC;G>tO2L%ka4|zaoqmF1DMHXO>w%aWH$la4MI!x%w!t@Tmdg^hQSARd zfSR2QQ^5D!xmdpnE5+C&?R2WrYM^=+{Nnwj)`-0bl#{o}nfr(}e`o_poeFSZ+> zHP@^zOQiH?JU2C=Y=l2`)eY5|Bbk9WFRO)EJrsv1;b>c{y@HLm4#18UdXA~~A{bDi z$-pmFS`R+jsjV>ApyPql13kn>t;?w7&>Vt1(0nbPadXpDO0k;}#L882FHui&m zS4sh+gHlf_hhG8{Fr>d9y!9alm=Pt@iUJ#<@l!Z^sf@rQa97*&rk!Gwy-)`oTQ$LB z{c*N#%Vf{){$^j~7_zkVw-a@Q$NB&-J)`UMy#+twB4R2iJPg$DBl#KxxN>D98O$^( z4K5jG3fqI96Laqhi?9a6Wl}($OMgCU_t_y>^)TGU%8iKP6T{p8qjP5+ZxX9x}KY%hm#b0cKb2T{e?)L2>bMWmFQ2 z{->JRhFgEIUK3nOVJ8IKwO!p(#EXDE`P=yLk)V=gDyWYBJ?gyo=ZfkLYwVKQuLj3K zX(C}GFF_yH>d1`MPQWGa5=2p>pM^oZB?VHwK7DpjXZE z;o88g_=>+07iF>zrr?hbfF@&mx&qzCrZoJoA4mxjnwdr;bImwWyjkt;;?9&5`1m(wYt3QLX=b^> z+-~R``st^B7O^4|q!c?K5+_yKC`ZW|G@$SY0Kur`Fu_$ErD(2!ELSxQ#@ z-wHdh;=h;vAMmSL+Fz#`8Ge%Lpm&fiXwUZu-LY#cFdtx7>V*uhcSMv`WZzCYa!%y! zCtkb!8_T1rP0ir**w%yG;(YJ(qj{tx`xQ&++Jxjno<%-qf?_@j@>io4 z)3|6l80nTvIhqV=wO1M;ovP>xlKHxQEN?mV${{kdp2=j(OZ#HRJjjWOeZQAw30a~KJf+==MTX87fBrNcDePOW|(V+TkpDiJMXs@2g3CJxc@ zet^UQ1uK#d@C_CXk9Ug+mbSyAr+;D;=KFiROLb$rbOh*|c=vgtrM+zlu;R=K1F#4D zfX*BI%w5rrK;Grl!XG!IC&v-VZf!qh6~g%s}Fk zQ)<2SV0!i96aBDM7d3^l@ySW~M5bSCU6w~Ipp51q5OVgOR#wa)Ky#t+H-QCQW9Au# z3C%q+39pvqu$a&RJLClLoVk)mR#iMO@$>blC#W`%J@|*Au(EHB^w_{qc!KPQy_>2M zJAS`CRWT#S35*yoKXBK^qJ@}tbkd&z%ogmLwJv@usR(1@3Wo<%gCaRoMpPrmp&f?M zFR%B#I1J6U272es+~&&~IgLan$AnLySu_ViY??rJWF&f^cGRjMAm*Q+N!ZW&Bwzr%-yp?wca z!#Ro=K=}mlEEsJ0b-_k1Xw%F9%7p}yvFqeCH`B1|6qnz4b7OSU-%H*M=G>fv7b!%O zzd3>yWoy!2786jgs-^~F;*fhy{(*d8diplliP1F$iWaiCk7^md2mu}iY(fcG$$&qm z1}&$Dc%}?*%JrBUf47WAjqNDnYnyKE5&Q4)@tkkpSdf0_WEcwlSnDc`L%GjLeY=m0 zs@*bMqXEeSmI?+tndDcUr($hv^=3I1i|t`JoE`Ej&Kp2-vFoV?((dou^`B`UjWMDk z@2x&dCPOA?bg76C6AgpI*-!+|h8r$X=9k9I%P7jiH`&iy{lE>7N-U5)<0P5)P z^pt9`OC#IN{|D3ni5#K)k;M#%AE^@W`TisQAG$#+UjZS2C_>5`#gE{a)BQK){oKF{ zk#KnEYB&)HO7`2cRQ;~y%?TuJi6yC-Ud4%`mN{aELjQ<<$eoh^>zmX*DY{<4r@L*o^ z&Ida#+!0(h1I3Lznb=*HR~n$}5GnD?6OTt|mqV3_fy@#-U1gJBBhAPNNv`hye_jA- zB^|3SJ7(T{6~u9!ZNLu@8L3wYto5KxMP{VE_|XQUljksX+}}uK6edU*>&Y-QysHe;fHwzS63M zj(*gzSH)lpBQ{rS>9T5D&z%W9V?Ve>2-^;@2v6%YNHOm&CtK;26Ia~mFW)?Sc;GbkBv^2}~7&^crW&v>~i^=kOY*R)H26)Zi*er8nH0`%U8W?A}Vroh5SsxVqh zE$aI9bS{$U2_;tJ&wBOfEQ1m~O-+=GCZhaOM#6eRW%~)@wV5{K1s)1GLWNOunZw#L zs)u68ML-M6$|kcuGCc&+i*#)K$1|`g<|84L&xi?;^M}wT0A=2TZ2&$5EXpKM4IZcS zn4t%H$<#Y9$;D6$t2Mo4eNYV6X~T=k8xcuZ`V2n~5fD<-owtGM@Vf(X!d{efMP`{^ z2@IuI?JVsv0*i2DWOEN78z&|v9+E{sc>J%=W7u$GXDRo@wF`S8d_HzRM1b1|xF$Gz zN*EX`x#vFwQMfK!&?OL|iaKLIIiQ#S>EftGP|K%IERC&7>aY?gY=|5uK=0gH>!~Hu))WiK%N9g!cB*gzCQy$Q0fLwr94x?s8y%!Iga7Xu6r^-Y$wP=qcQ^XO_}Z9B>J*?(PtbweqCyPZ zUHo_O^L+@Q#~A+(XJ?lyMNgX1chCdUaYZ||7e^EfR&ey4tqiH}CE%ACiP2DBj-k-1 zMFKC+iEjMy!r0hYZB`a$ZbolT2WYYDrX==c^FvqVm= zu0x)vT>^kvqPz$SI#`<-S>(P1g(9IGJ245!Y==H0=odL=!Pf|g-hrEpT9$R za*!TD^C!%RS|b7mMmpok=6f|JG3gsFz_G&oyTF)bU_&Q*`3wgKdcWvFD^fXn{#{<~7k~|N23C+kbH1?^6-Aa$yYJIPb zSA`L$sFj6{4L+k1`{B;L2#<~~;9n$%@PL$KxR+T9hhqaMX77j%nAet)Q)!EC+&Pa~ zNB!@6)o*@5Ai&%MGN~i5;`TcFf8QrOk&BxtkMCTX1es=gMH-)2gAg>4L0UnkVrG8; zVgRmLoe~3ZA$#*!)L&*`ZQ*Xct|VtvNxY|=NQfPl1H}%9Ex z;?wY`hlC(THFjjrVkphn9jeVUd^Ac_IJmic;AHGP4pThMx0hR=+ysiqV(e_$l!=9$ z<{|+Ve!MeF0igt|MgKJ!#u|2r>7J!G3XWcfw4$sMJX-D=Mb6xr4P;d%PVR7jmro~K zlNfQ&Np4Rowbq_ksHHm<=u65V> zd&EB%{H`iaj$Sl4VLgn=MMNLVXObzj0p|lMsf60KsLIRw)!P_-W!C;&d}?z#2VQ%B z6Iq5Hc|QzNeL*_0BkV8*QBI^EsH}YPOxdJ{BY_8RTW>s?zy+O@AKU}LPmY})fHQL6 z1bt20nXOx?Ux~wjNZcI%`X}%?5`Bo9Visk8jbDF%dpNL%@cpaxUm3Oo?F>fYUv+mz znQCuS*5EF%IbykH(nKCgYF8Hk7zr5-KdJe%@c@q%gwU^VFFGvZCBuQt3H;_PTJqpC zxNNm?)0RP+2Yy}<{-`t^75NkBHVL3Ol$Ht^XE0COAHTv&R`YZr_Zvx7+pr~v7C9zb z=^LKtJ62`>dD&VXjev@*C28`!+Z^}U8?CX|1(J`V4_%FU0ytB;*qk0)s%-dw%NLU% zAe)4Uxkp_C(udyWz)qQ2pd(OvS-kLA!i#6Ydy5nIu>>U;mRfRR^uh=!j2}<)GlIc% zFguz$I&wn(Oj*Pa{(VBI@gvHWp(mQa9&rr%6_DsIQsx&GP;U-w$Qyhs&L&L^OMqch z*VmtRlD1BcQNz10g!N(5=U;^2*5X}B-NKj?0hj>D{({e59$BdOcW*(WgkK^|@ZjLK zGC_?Yw^O17ADAe3;B{y&A_o-rG)uI+Uv2{URDAc|wp@IBlOyW2{~GcG(EK$^!*Il( zOwWZjAkS#-HoaYJiL3b-dH8vfV)nm}&stC70>R6Fih_X%Ft((j9~p8|qFag$>+od^ z1;20%ycuLrhOM#|oA=@a)~E-iKqV0X>kgn>!@(uxU@LEji1(^(>E~r?OiZGrbFIg(tw6m`uC~ zF|$qoFOft&mmIEhnErXIEceM`s`ed@rGjiW$;)TT%5O?PuTo!~?za6d`RsDO!9Ww> zJDfCoq-PV?Gb7#?CkTk}Lq1<>F?Xm5u+f3?Xr6+U+?iVS}8UUV?IrRRwo*OdM| zy|P&W-5DdxjE+87tedpBYw-jBWd7%~uh(;+=hO4gVh|8$phFCGS?NYAzgu&!dNexZ z1Ki`JW#3QJS7d=aZVRx$p|RAxR)6W?qg;^N*3OP3Qal{)h%tuWP=|dpp)d#|2t0Au zm;J!u%oj&%2lle_^;>(T$|;TIsJKc+-s!r=Z8{*<>`ul ze0<5-K6B=oOCa-+>@UNnxTzxEGRBq@jY(b3fR{< zD>K_1>~MZn5p!cGwEQIRp2E`h=?->>OCX{e@1eG^tYOm*e&67>-hi!CJ;945ewV@F zZ!5>`)-($@PfZNPaN-vZxK1UneN;C{lvg?)hJ#7he+(ua|6++CAoBiWFZ!hlfChI? zfz5^{VAzNt#iJi!V;<|DsUAz4AZxo#6}?97w*dr`+dM8J1N4Y)rJrS1?GYvp{HhL5 z?10-Udj0(_6G!LkR70+%gWuU{TT-3;sO3 z9XQoeSF!*0rMYs4jYz24#=Bcvqq})K+}&mMhhLex*c*>~lr*Z%s{V02MtuK$TH)l! zF-Df3<-#(w`2e#1=enwCd4T$HTmQPym(6rd!l2*|y3!wax5K{8$D>l6V#hynh!%eg z{))&|yr+&|+M{`P$8B}hE_S7PBFvT3A41d5KBG| z55uHLTU26!f_v?{@E$7+eTqussjP8q4x-G(9qHYkbKwYVs1qL^z%S&Ks z`{o;;6B_9aI2R}3e9Iz+dH-^+gJmOOGyun5EogGrM)lr><25N={TeC%B#UtY`h@8e zB#7>$UXe4SCh3x7Rf7p#dj-wL0PM!Bm|c;;I-S-a?$61mv!P-u)dQvN1iQDAyEi+- z&J$Ek6`P|}df(-r^#w*d^GPXoC`K?~s1tT%c`p1oMO5)@cjBw3OUuvCds^(C^1GZE zpZz(L{v0YrH`paf&>EQOdg&;5W%17UXWSRVo|$t4cc|<-dd`Iszd6L9wygcT=MC-N zNk(Ay_3h)icRMoM2A7I+Rqi+l$m%!lgCX(Rk-TM(xsxr^rJhN=?l!^UKW~Qz>R(^R zJ5O>ub!G!-YQh;w~fFa-=X9HrFUKCR1?Y)Uq=@PB{0no{Z03QCvQymTvP4 z@PP=I?1Z^-(*+$K4mdjv$CdbS{BT(}iCi(Lldka*G%>pJY;MRSdNM3^pW-Agceg86 zL}FWl=F4_lc#5>*lKzB9$(NWX)SKn2RST)7`Su4VB<+yPXDBzuvWH%XoJwcJFh0E9N5}IOY1Ek zG%Ed|>Y`f;%WjDgt`#!3&G++i`5i6d-tFnUSXU}jM;IuZ|HWaiq~5;G*OzCRJY)LK zUPSWPruq8RB&P9NPbp%tCz`HTWG$UvgXW5OV7)lZ_ki1Z>%2|m8TydOKP=yweUj$m z_Waa^GCJ%K|Kj`jZ4EY__jn+Faitxc!_ATLaYn&7acE+h0{1AgNCPJQS&d_de_s>c z8MNZPpzwIcw9_&ZO(7xj8)cZy-{eBwM1efbDA*lXGl~WV$7jG;_4}&tT~6xWf4mwX z*j(cb@NtV^4P+v3Q=noUb_~SJ6zdMJ^R4I@}sN?D-f?jEn(JjvLcW|9qbJcuXp_ z;WeI=h%eWWlQ%WD1N`;Kj!n+Tu^2}>zwj?p@PIin%sVBoVUqG28B$keA&tm;%60)e zB~Wa+-18$iVk&!``-{c=qZq+k>edGDSF_;?tQO~Zt)1^M#O0!PI@YN@F`81A@_&6| zZgJ^LnOfxd62WB~9ic!wQd9ik+?N8st{3_cxZyK&1gEBBWUZyB!FF7T#&{xNUtx8ZoP&QR!P&XT=a!MZ-f`O~}J z+97PB?C{F#3Jqp8P527)Lhm_rcN#BYN@`nj486eur{(%gLZar6Rdbyc!K02$^(kD^ z<9NAGYoY4nCZ>)@tDtBfGt?E4D)8ChQ|Rm?fibNLCX56J;_ZIgwc3LkLwO z!YQyV^-D%7v0sn(1a-1hD7525Dws_ydEgB6LA!L72BUd5F~fQHKSH{v|5b_QoQYzn3wbh2&HGW# zF3#g#gtBRwx^Q`uLqtwtNuAUW6h0AcdN4dY{T!CRW!j0OCr<2`aV(iudC>aF8w?1dvto#O?o_i`BrZ09byT4YRpJ(ry`<`vM* zX-Bpw{Y<~k>MqdyKYS1I>2Uc!r%e9MV~_SO_glov+7bj57>2*u2O(@_wYY*c1?!m^ zZPu>BGU&?V4+$cqh%vJlQSugCvjayT&xBOpuu~4_wZYrZ#?mvKfp0Fo7;aC?pqF?X z(JLxA40LnB!dtp#b?(?~@!ahde(@NOvU-ATe3mNxdl37*)->qqj6HL`vtOI z-raX*LXEkH)U024$mMZmB7P}aSPtt}oG)FCx{N)@aFbJnojG-6jo~<7@vgbmqL+Qxh3wtFmy$+jU(>G^L=(+Gj-f7bZ?XOW>2-FSzduPa)JdE2 zDR($hC8On%>UxdfE=2OnuwwQQAK0`@n_JZyhvP$9jaN7k_lCp7hWK3f@AvNsev?dio4U#UB~MRRX?AT5a` zS=Gap5jGOomEiE-zH=V7P~^Quv}_QI#n2jl9=Yp(J~AuPXPOf)Xn-Uj>vhG&oWDd+ z>zGepPi**(DubgCx+xUVpnT>PlyYzWFHG)}bLgR{B15TchulvN>lW@~+PcPTeOH!S zV2g9b#P9qpZnp|1eUZxVsiFPH|maTimrs(Z$`}t+=~Gad(H}?(Xik_`A=&_xa9m-u!cBXI65O zY)VciNdksY`>*_T(QD0A4H0+wW+fxEmI`PU$Ob~938E!Ww`KC( znc|HqgvOoc9-%26N!Vc)b+4#NN;9MG4>tlGJaocH-@ip_HjFAhE)lRp($eukQ^?~- z=dL5}R7G7Xyx<{VJeGGIvK?r5wz-wVEaT?4L$=C7w}svS`8_&PBu8<=NK=xw4K3M}DT%z6Xi&pZD-4+|$V zXy&QXF@d#XiHV8ulZ5)oXT|utUA0G-G#=Jq3ey>2xNw&kt~WOPxEC*Pk)_~}FVBI%j>5W88H_!@Z_3-Vu+6o$tXzsSec*Vujb z`15`!qY{lD1GbUS)<&ifkmHrL`hs-auUVizTi2s?nW&(B{DD`WY<;;l$TJ8O!5|L` z(&#k)(&@clQs8k=!?{!Q5Y0A}mKaXLLii3uf~cUwUO(8km@Ex8;Nv5ev^f4Tv1)RA zFn$D{qi3xC!EXy=z?K{V;tn&<5}SkFT%_;k;tb)EEu6)_37iAE5NPUBeW{fPEv$Gp)72 zcK>oG6{5%>*6@puT>#aGUKw?vHz&T8ILk^|bGZL+N=T*lo$_<;2FAfy$4&kPc-KE2 zyK^;-Y>5y&{c>c@z~$O{y=-f#)Dyd6|1O#=SMvNt%?5|TNc?4X8p~(rOz-Doa79Y? z8)E?P-0!c40FP+~a+!GdFOoZkq)&_gk?ewHyx+{o5OO?uCU4(d6b(Z10-siQU}UdP z`$1*Z*C&kPkd$v9pXkYllPIMt`b2gCqDr4Jv;Z!&B+VrOV)xnlYFOZ-M&W{p!<9PW zVw{M;C|-u(0$5Qn1?H3?A$A9&pnnqQl-_=QUPk6x%UNGg*D5k>90v>kb$Cd8-fy!T zW=zEuZBHwjw5-dmZ;JtM@J$=;^k6Sizz~TC(zY!g*M_T6o0U!LF*X15QT__N$LtTT zW$SoKY0!mBSNgmu1z6M?Q8NMtPj=vCsEEP>4&A)Jo@fN#+jK-jLQhJ3k0Wb{hEVO@ z22DwQ{X{E7OY|+XcjR)hmac9x@k+yz_LmM^E}4!m^66&pFim#ajezT)-GAEpuEqrH z@C2Khd%?K`7$pDEV>CMB8Vw&HUd-tPqYB)iS$DlX{CPBTT(xTA>6C|n_sb)|lZgw| zwr(k0Z{*tataJ7N_lFk5(@}m*<0>ak1l6b9=f$EtFpRlJq6fs}3HSo7c<_4DMhkZL zcHPAiPVjw*u(#h}aCUw$J>LTmgMwn6S7|>>bQ>mXwahn?*FW7mIIxGSf7~ME{rJKC zG&d)V8{_2h4^Fl7&-hFgJR<~n^J9tk^~<}U?=@1@tJ$JZv+K0zllr&`;4 zd7tO_1^K3R=kx~x%_OkkDKc49xY993t{e5ot&@s+N(DjrXgT#M{P(;#CCBAC%E;wP7wHQ zL$B5Gt3(Wm)$>0@N4-~RE?7^a0oEDf&=w)&MH*<DFrPNdk(6St!Dgm-yB_MG6i{%@QbR2zR`koKm!==Nou4EnFwZu1A?0+PU@8}Vl z4Hz#{U^Vu2*qr2(PGU-=l-DN+=FV#B#UEtkGq$-n$v-lL0!ouUVmEdPuV-~R38XQA0q zqsqnsWK=;=j^ztAd2QTf{9Xjvyg$+z1^LHl@;^4ezr^4jR{?Ce#g-{pjGVeZnoQ&6 zJzu7(*~o)>)!&T2SfL^m8(MFZ}@K!?BxL`ru?taGQyakUMzPIO2&{3 zPE$yBSj$TwAdu72p9b&D#OZJa{ofm}Fhs;PqYYM*7=L5Kc**hOQxz7rSg30~oUaE| zXmjpf#foyj2WGWcqkv@!|0#+&(%}A^#j#j!^FSp?Cz!7Kz*k6Uyw|3bhJv6CH+0wT zxReTT1bY-0LCx=OVD{0{yob-GN)jB7q_|QTL16{OxhrcI*{ArnQXozfU-#7LcTB1C&XGxI++J-P1Bihg$D zK~7#+^DXaMz$9K7a2yA@Ui5*wkiA%rlge3g=%;j+2#1XE52*sfYyN}0%Pa{YU(IC? zvP_mDi0{7td9Vb=ykEzG59;RP;8`L0_nycvr9Ka&De$`zSyx^JPi;J2osAWyTub50 zwRm7fBSMe(ab5LaW(~G(BsOn{6jQWX3ue8aUgjpOhu9z=1qQaWG!kBRw&51)w;*Hp zJ?939RrwrbQDxk!QYhMlrZWprNyB9`Y!o~B>aW+8LR5U zLqKrD38_=d3+7o&sf$_|$jr(A$iLv@jORsH{1XI!eBlc;Uyk`<(-jcY8Jc%_B|F^| zFTG~7R@4XSIW^_$A_xfGWg-oUh+)&^8fJZE;`uSy6IEVw()UeAOYqZrZ;N$|pZ%xR z4If-mtBsJjTjstkqYiVjF4GI;H0PbZ59|J7K638EQ`{Zy|F%k=FZ}KjV)1S|ZrS5x zubqcpUre%9|HKh35pJ}>Vi)c0PFS>!sfRyu4=&ikkva8eYU1A_T&d4DX~2bL}UK1k7A9F zXOAU9*IEwv|Fs4p-*(h0L2tgw))O3lP_JBySKtzO!*BPo>uPb(bv3Mb zyU@5=^rXz-zVo5bbjH)}(*1U6rO+wc`}=V_N^|n(vILBH?p(U*i(YAGz&X2jsOg0l zo{yV5q~500Jp# zJTC;u9QgD_8%TGQ9(-LbW+}v0gDIY0zX94YRyYB!d_MbaAfLxqlE)1P)C-WiOJG`O zKi?%#{5q7-Zb;rcaIP7@DI?jSSdvEA@laaN*KB z<_9Ke9|euGn1+buD)^{m_;7O3IFVA(fuq9|hoQ+DS5yAPw?0soRGT2fGY`(&Haf!# z`TGVjZ{T!+qwt|<)z*bJ=@1+@$^7Gb1bheZjK>**^p9rbz+^|b3t&Bh8e%&x>&Rz< z3XiLh=xwDV2Y+?Ll@Klg59N;!A)oeysJTHaX?N#=yvZ(ZmsW6v1qRwl;6*V??*KL? zt8>XRw-+1hnUyP)Ps%zm!0Yw9V}mx!{2lxWi7Q%mbPH*KyNf@YlN!Q9#~tC?U2+V> zo!C98cL;oklm6Bq>U9jCcR-?tFO&K^EUNx0ZV)41wRfM~Uxe!Sd*&%ma~DU)0!9?f z*S5eTld+fK$?ED7SfBPbguz+SjYm3?_idzhhX?uV!%Jkb*eAU;3!+AbHbOwA(`Smy zXMxI-&6);@HvH_dHq0&!tlq%Q^{A8hRg~ZDF2q?c%@EL)Pk1i+_h@MnA2>c4?%(Pe z6W&0R(131=^iF@i%PtbrRMjf-@JXC^bkxdMG(OaZA}l5J=yNZEi6;w~!5DtRb#e%u zXB5uPHx}#mM`ZS7onU={y?|WP?8mY9q`m7qd*>s!_0u^$x8Z~FCgIiLrcNBF%EezH zt z-jL&Em>%OV+M7kV|4i}O;a)XJfRAY)5Z3o1c{jQ|B!~TzkYKpLi?;8?`m`p!J$yc> z*>LMG36YsOq1zwauRM_8=c;0xb)pNj&?kWjUerSrIw)JtiStc(mkm}phYvOsQ)Gca z0ZHFDWjKSMT^pfWSQ$mD`rzot3K2#1S~Sbv4KJZ4^rqbf*^wOfiy_=g!4S8}R~#G9 zceXLm28?C}PW<;%DIlYu3Q`lKQ)vC1miV#oz~aMV^#dXVH_W2ot7YU7NlaUU7xR}2 zml*G`Ly{+s_rnTNc+?>jU|$<^mtO>pYRV^JV%Dvbbe5VSxFg#Qvy2^+&!2?M1%2OY zjBIHr4B z-=(+g7Lci>Yp2gD341;>0^*C|j*EptGgENg$RrkTF^(9#vwyWnfiSVW3M_0!!N=)9$3&^z5bk>6kJ}?kN<|xNEVJaO< zvB%e!Yye?IH7(pX97a)ipgaf7;z$X2N7o@8OMvnDO9#-o?$-vu851M!cc^Q}LHV9zV^LOn#0_!nX+l_ z?K5R?EB%>cAUhbiwoVyB`4=wt?S={l04(e7vvQk`FnYH{Plct+Cvk{nsloeMpuTfj z0PY~`OQD+Un>Z)!D$r*P5#)V#X7l=L*7tm~GUuEUfjT3xaQ$oS?2mtRpaTd{*q*F2ncrWto#E(Py2G+wQrOzo(+*>mHQ3Hf~+rEqf~{ zu^B@{3AEp4Wemw={9C7l zx5RY)Kn|0x%PQK?Z?0B);>?NNwD;zAi0FNozB?ru980Xay(yJEnrT2JCR7*I-y_nr z?~C)#piCS~Hv7;g#gblcg`|xw-7G;zKfq0CHm4{K=Gr#kf*&g-(&_ZQY$Vw=@q=nQ zL7o0sj=hVt7w(mqIOZ7puovi}CKQ^%TzhacX`do;f&Zgftno50!gQoIJ#!Q)24Cb=bUq}9w{8?Lh;L#@?g;r6y zQfh2&qebr^lBCHu*`r_}*ZpDQ{ZPR93pzAI4mklC@mNa$Do-ZqM?S^!uo z^9MDX^5|K{q`fOOf(J)PUSanFiF7`_wbErrIzG8eWX=9%cZJz|xc*>5qi(X=ZW@F0 z!#$J#?i1(9$du{xRCj)DAsD*TZW)-23{kIRqYBRQlcD{-H`HJn(Z{xbwz{X?BOW_i z%0Um>#>jBAk<0HCF8QOGq0{wyKs)+35Q2u;CGuBmnMk^Q^?sJ=XmxY^o7$JEnwt9cqQ)pc17QxDE+=hqs8F{KV=2P9X(=MzQs1qkAOx>T$5Nm2qwXA zLu&6rhVg!ZJQ-pY$8Z|&var@07WOx@f1CW$F(4k6a@Wc2 zSoICJM{TOBHjD*{m4`0AQXSfvJvfXF6ZX>BICV>Yi)}Z>*RNU`ZgFIjiAk#`1|f;A z1Sj0rs=~~;eJ2X}Xb63xPrtsvlmk9{5_4Jd_jm}DDatrBnAjQ*sn*}WVD6tqDt~-o zUw-^Lx{#4SeARkn)wKM!t~O(VWNhd#i7>IM%gukd_PsPi=N7V#YrWgnn4YFiduAe^ zh%n*D8h3Rt$f=DxHX#C;iWk*K?T3}^B z_Q7;;7A+*tCDyeAZr$b0kJ`v@TOzLMB=xtgBbB<6Eg9w#=c*xc@-f@P)OwFNOOeT- z{SsXTq>B$u8v!k18cT4rDYFqu(`NtIXxBy}(}_BHgGQO70K#cT>rXKYE|QuPrmLm? zrwcR!bk%+|8B5m}SU9FbHw%$Nqic@U2SsraC_crqe{@~4I4MqfMaYbA`)iR1a({FYrhz0sSMaVEcowFCTSi*L+A5&8BmD!%N>1y^3>0j(U5+39I@m)z@InUl&7OpsJVcCbOe60_yS~%Oas6-;r zPeXFcOkR0;`#>{<`DeZaPn$j{iHPq8v7iufrKaF;%iZLf3l*O{ZQkwuO8@%Rz2)xt z_kh((7jBrHqGvV|EDQwrHk#~$;)nRzr`PTL*IIMv(}VVjl_PGG_LU&AdjYWlr6&a0 zX4b#8Kve#uMDCW;Zj*v;q}uWB)F5Ryn_^P0>`XbtY@+DOl*!&ETr}>FUuh*1wPp|B zCd2{b1$It$Y{ho7SkWZEe=JJ5TJnM;=0*yqO%m#&_g+S!JZCySiAho-x1Vir^I zPGb<@GpjaO1(y{|3eQ;ANI7f0-~3Cn-(>`IoSb^nJR)Yb53kia*+}_UbLI@SFSo76{XEQGe`CDQfz8ZLuCK@w!Ta0g?ZqG1YlNjq@x{O(NrigTGn|@ zciiRaqQuY10Nsu?GM!wg#>WmoE|-`-Jy6yauGWS=79((BfTSoSq7|3S-jELZM@l8` z?OZr}B&-o%p47|D%$}PuJlIHlse}g{IEx?k8Sh1M<@ix0w5I6eJI; zPd!P9z~@IL!Hmm3$*P8d7d?b%9VzP~-4*3l+L{BZTDMVg!w^XWo{p?+YiM3%Jj5@6 zOi%g*)xa@ItBmosa?Epi4z2I_%Pwv&Duq9Iu=IY7k2PsJ5dXew=E48lTAN+SX7i;3 z5Jlp*A2N-a2vwG@7 z7j9=;Fbh&n(JEoThrPN_i`Z82y3zrSNwvDu^)vDpx@*2iI3GN`|MG0u@~ZEt!&j;U zcF-64cnl)(^_C+F?(ecQ7Aup7c~sGZ7ht#x^%Q5#Mfuy^v~8jL(+OV!EZDZwt28&g zVb^Dps?XX{J4~Dl+LfJ|v9wS!0tJPqerK@ET z3$JfkCY6uP-Sio@i%_sq02hD6CTR1cONj<|)_qQ{QGz)vLn*uLX zjPnl-pCa%^rwJ)Dr=B6MhUv4#@aP$g9bpH0dQmuZ2}H_w;kxF>;@Ybrw7ipuC}90} z5r~!`9tS~)6M*tTdyJ1Hx17!GT%>7I&o-PMo?AJCB?;SH0 zQ||Z?ThZ6^bg$k~hsJ7(7U+Q9d2Cgm#zeF;nX(AZZV3Z#>S0rtYDZlRrKm4+&ha(B zh)o9MQ^jI32XYp&q=fFLkBNwy60&``rkYJqj$v&h%!J-bEL?V~e-Q?6Vl3G*1`1~j z{umOXLhC6pki>hsp3Io=4wQ6!urn73_>725_g=#|Y7ZYHgDu*&2 z*M18JXxCkEaYVt*b-Ix7E&H?bCCY{@)VxB09zuK6VFuXh7N&34{cg;wDHYNKu??%1=`MUPODWV;51v(b2Gr*+>scc_@6s*@v7f&^ga_z4@&GoBHLR$*$g~15%^$2mTY}Q#s=CeLlm=d(Ib(hd5jg ze|-6-AxX%&h+aNRs97%SEyFYL30Xu@)|cqfg(zhF8bQa;kaC2t$5Vgd3hy~R)JVmw zd17li2y>EioR>aVlBV@$2}tuRviaAdZ_0RT#cY)lGvD6V5JACxCu@wPGow2HD_6EbXxnPi+u{iz+2H%NOXnk3JWgSDc_^qHqYWJUBqNjt+vI?u` z2p&ZjhoB#9<2skD)2&h@5tf6c%&4(m)PBpmn6~gXazoY~$4?5}6I6$~*nR!Xdbxh) z0Md5;nBAbmC8uej^n*tbb=PUDs;yzfn=lXOl-mlIBa;gaClWr)U%4I-*U5MF>|x-N zd!poy#ZQ3`fpi;{{6*ROs~=N8q~Af)l6GL(pVHOUE9MGua>()xgrws8f6Kt-_F_X7@uv@8HsT7UU7T~8|(cEx@sSM zSZMfU=6_aTP<~t40U3SAQGnk^*utU3u$BuP-f!MiiyZg(x+}e>VV~5fT4tT&ypWZg5T301=o$|sFmq%MuUe^IE3JBO89f!!;+OAdFS*sLf{RzA zZfw5dP48|S>!&1i_Sn>Y8U4m-8QXkRash1cprd4RkM@hWsDHFxidh_Vrhp(EOsJ#O zt}yoE4IdI@6yR4)gS6~uMLNQtxGThTy>Rttbv~5<&MIVJNk9&JKE7gls#}Z- zDLF7K&53WsKGaBK!G~jf%TeHl%Ata}$;QIof3?hzhN-r{NQXyyD(X*PaJ1gj_`0cI zV8}3RnaXX)@pYi;(={m4Z(t+Qr?S2#H6cFve8s?6zE!MsNkE?cxviZpQinh7bBQ^N zJwv7_5xwMaYRN@@>e8E@mvOb*h%F~Bz=f)8lzWh0jTjlnTBqG#ST}&0YEGn3(#r7F zU^f+OER)_oJ(iXF!uU9DoTxKFBuO(W-WWgWe!eUK?l)UljvEAqDQ+YCT@m3tteCtd{bnLBAYd^0); z(t@^qU>S==CwrU?P9{b?HBH+9+i>(e|EvR;{WqPj$)R*qxzK@J%jWiU;`E3RrKqU0 zKlp^Km47uxpo+?NAs;#(PVB9x{Wpwp5iS^q9Uu_B*J zp4%A_g-Xa0lW^%&VkubdW1iSk#d;Wb!Ex+#y-m%0!gtHcv+3;O1wXq86 z@Jkhjq^?G4lxAtHPc&sY-;dLm4fMPD_qnRw!IRy?W-BI)J{hv(tD70&xVOQ;HjISI z_hv)NA&q4YnIM~0+!Rc=xJ-bJ(NGqJPTMp6Dc~cKcqrTSAO(kevmvOr0oLhl%QY^l z9SORzt9>js%Kr>%sx@yuc&gNgJ-thF^g2skx!MGfL_K*eQ-rdr^eoV%VqcMffsI%`CI2&34$D=HtC%2yJ04izBc+PvfQX-{_u@Hf zP0h27yN6KB#;Vc7mj~x{LS(Rfcdg^zjH%l;I8z&(ex>ri#R{m{h%GkJJ(`runrxmd zU?wQ1l^E~-%&7jl@k1+NE&ZFti~^2#Lz-J1SB`DOR;*$?o|5`U2qIM(qL1mVKdBTO z{dK5o3i@pD)QqTKhC_OUhk7-mATD9fLwLdZUvx*uJrI4kUX}}J8lYZRri)X{y zOXq1Z`{I$WmlGwgn#@?q&u+pmAc9qJsoR|~Zeqc18M>KW@odFEx#RLaPSQof&(;Z( z%Vfe-@$}nAzwObamLULZc-BTxc|{M5C+QEfE=L*@Le@8*tc6}Iqg)1POKmuOR+!Ck zA%xOJ;dT_GXrU(jrFJ!-@wHy9s1m&Y3ERfbludr_Z>&%gnM{}pddjDhhX*ejD3#|r zM6S22hE2wL0%38Z0%zJd-Uuu9<3WYS1%+q}F8t`c)n>X=Bj(QAg>(;vRnj4Y?irtHXFMt53P5_OdEWtVw%+pH(e@RpoVn!8-r-`;ezdzr(SXH8!$*_HVvJT>)$?M%=z(!*YcZ(N!a$CV#pcY*z zy*1WK-zjIZ0f=)_De8$=-NY(b5Y>^b61Dvf&sKj(yzeqJbuk*{?dL*7$+P$%kRND% z3n@dBEn%0bUQbn*E)>>Gv$~J0UrVa)m2(d zSfv9xEooPvL~J*Ope2sw>gL%VsL_IqWz?5q^eGBaD+nrv`pvA)5tcq_&`9u7cnBZa zHj!*pGXywRs6>39wFDUY^k{T*%SgN5TyFmrP`u-{y;MUnFsdIWQdqqT>r0)W7Z1ok z4m$^~RL8n0FV;Oxn|~)p`$G2}@joCh+H1Vx^UQNUKHisJRhsI8qJ_;BfyC^ z#;3i&zc+?}9Pazh{`3ByxOGE3!CQx5_3G7`ua88CWSWfz@#hhwnn^XwXMoyKz?HwRGe}`5#b)P?eM`S13r7)u2gIX2ypMbv0WAYmv+8+0v#sW+%r(~p6m8> zqCU$*&@VThIO1JVf&+66r;OG^&u9Ertg$^diR@Q4N!anZjgQyr7 z-_w6&Tg;oy_rgKkhE;)Ry_s>Xe;Kjt#m0JO1@Oh#u0q8X)Mr!5;*`4Wf0eQD%!fK3 z?Tyf0cAMW|RtwNYqaTb)GSV;ffcWhb$Sk-aX848d(82Ds>&bS4ypf84UgLY|^=FiP zch^rpNJ%HFj~E)gZ-|HNjfH~L$64+UMv0``cj^ zmQLOxaOv0B>1v~$;Nr%h$w+>V%I!-H6~1y7x@PWxG?m|;%$wl3ZC7i0eA3{Zr4_Rb zS!w3fPs&9z=qSLn-*5X@e$9d69;uyadX0>7%0mo=h<)Uz(vR` z*VP&CkTZNN_{+*MmW_LB_>1U70#Gxwr$6p>I?b_d>Cz5z?Vt1Ln^x`T# zgY4c7pA}7RSC3a+4i+;;O6zz^L@We^6w55vSRb9wt-*~meU9gv zxXAM)Ect^Sjld4>eS6mB<`1`oyHAT(fpZbY zZLo>YL~t){`7Ngz8~T86PwH~En55*;PEt}OP8KZtir0?n`zz|=l*E3l>#imzaNke& z1`|n}>|12u6aNJv{kxK9vchY}y^}YnaXsi(fSd*7xs^*4ia#_aYxwPe7^4SNQ+Jud zVlDksO_?;8z*paxLP*Dw-GG%8341vftJTH+<+!nnY~~#uflsK3v3qRM+`!C0Wg(kZ zSYpHVHB>v2r65>HUItArX%|b0A=s=E6~Q?KwVT^$Rbcp$7#_Z{2Yca<1VjYM&-H&G zjF-KURQF7J#eyjlT!m*-e8zoZFTC=XugCH2Q9OGBq4o3BhEo`~rk@xEN!(*RC08ui zBNS|RM7|6iL>mR_MJ*qrZ-9Q%a*P&C&7f_VVy#C{8jePZFj+rkaLI~0yG`*l3yQXv z?=lM~c_xZuZi?Rad?J@Um+Z}#2JpIe^fBWnYjFOe9G#~#t_#{4+C0pZqtfDCG})4k zu{&r`)oH7ZbK4wZ5#S7?ig2-oxe+dm|52xucR-|Ex_^dz!A6=mT+$w zH2?FLLuUsR4V|L}e1dm9xXts+t9Djei#tLi#ScM0Q%3Z=Ek%wwa|Bnrc*QR|_>eh_+Ei8RJgBiyHb=`~0u=jZ^3J}J zkdC)4yd0Os>(z#C?@BDq#l>oLN3CK3AF-S%XXDjhy~W4)(ag9^J4XMhfy*LtSt-}N z>vW}Sc~M6LQz6b*@134;T>TC?Z(=L1Yx7ddnbranOC&yFk>{k>y$@y4`<3gTIH+aX z;wg$o89dD?>FaSyJ`l1y*K#s0{a)(p9 zy*GX#OjK>BzqtiER>7%H+P3!7QdTgdbI>=jO0R}OX1=;Q%u6y%@e8k7d|Py8GI9zB z2n@0JtG33N*`6|bm*v#f0=b9Em;r}E!aS>PTt%9`1Q;J?A=t{f$n9H`S>a`XQ5*z> zKRM3!q3$xTtAng$cBm&yIMIfhac?GZeaedV9h+`*Xd4YQid_r`qmNzG<)&;Ry1>1H zHIZeOBpmNTfV}GQkYI!Qa;-gPqs08wVTQqM97Rfg@YI)nrcl^9Uj{mU3e6*PF41L6x zfb_E~9fsK1YTC)XZ@=Xzo~tcyv^qCdlA1i=l)0=CnA-;8tF69}T2=ecBw8@S&emHY zI|i#TooV+(7mC|0akv@xv#dNxEfpw`WZn_9g0O+QH}KkwWIRupvsFyzCvIfY*6eQX zcohKMk(-twp?&c;KMr&BW8fpLL!jB{tF*j$Ix;?$H}N3btU0pm;^mI95|asH$-4h% z2lWk)>yo?N@g+M-ubKq?i9#dx6uWEXpQU7O>3d4a#YK~OgTYR()gM^N)~g*ziA?V* zRkI17Y4C^ZuqUHC`*BBI?0WY6n;e#Zh3^rKPaR`k>(z#5N9%l<1wvLZZy=oN?j}yD zoKB>?zqnaBVJt3s_C+UAxRvA*;>wkp&wMM$=*8YADsrI@MqZf!1x08OYA5F^ez|kE zLKv~Zt+RUvVi+@e-}BzS%EqAYme`k}oQ|hRR^9Fw`LMmvOsSuC-!cYcJl+`L;aVTu zx^S&XmN-$A_>uC$khRQ$<6PyuG4wq*2>D5*%S&vZM^cYXoGvPad}q@E!N?yKZq zV6&E#rxJaNfJOY0WnLV-i2{yug~CMf1PS~?9K2LNIo9{jHP;|ECG`x0dHtwPT^#6m zQ1kH<+->~HPtZ#eA;kBsRQw!C_!0`L7VNjm2;{jq5WI-9+%3Nej;h`C+uJ4=@b&)H5xK{Wz?=dTJ$nm*o?C#QquCIWJe{ruvf!K{iGr6%l==U%0fPVZ>J5h zetwZn8V^Nf?FNKZ)qOoqg>AfjksCzeLmz&L4U}at^I1r(O!S^NvB)q5HoE!`_ZilhPATkc zdQ-}0W)GFw01TN4ptMkm4a#To$WKPV(}Tfq>zH4I_7l@A60IGg&EVGI3z}X5@dsRQ z&A-c#4;`$Hnz8Vhj?44HjI%#Go8^Fy=Af*O7ex&-`#`K!BJe3EdXY+D*>B<^`IPH1 z=@P0EY8Rp}Z19wn#%BXs2?$hiB7PDT+b_tLq33Jo%y_@SniNx`gO%{G_D+g4bBC_sxSMme4jyMzmcD9FGbN(|m zj%)dU=Pn-^;ZHm4(mP5?b!WN(!hI1+tni~WxGTaoFK`6x$XZ^+~CX4;)D`2&UBt?7cNNQ90b@Uq z2uQG%G"; + padding-left: 1em; + padding-right: 1em; +} + +.markdown-body hr { + background-color: #eee; +} + +.markdown-body .codehilite pre, .markdown-body pre { + background-color: #f0f0ed; +} + diff --git a/ros-realsense-nav/turtlebot/install_realsense_navigation.sh b/ros-realsense-nav/turtlebot/install_realsense_navigation.sh new file mode 100644 index 0000000000..455cebe267 --- /dev/null +++ b/ros-realsense-nav/turtlebot/install_realsense_navigation.sh @@ -0,0 +1,10 @@ +#!/bin/bash + +# Installation script for realsense_navigation +# Requires root privileges + +sudo cp ./robot_description/kobuki_minimal_r200.urdf.xacro /opt/ros/$ROS_DISTRO/share/turtlebot_description/robots/ +sudo cp ./robot_description/r200.launch.xml /opt/ros/$ROS_DISTRO/share/turtlebot_bringup/launch/includes/3dsensor/ + +sudo mkdir /opt/ros/$ROS_DISTRO/share/realsense_navigation +sudo cp -r ./* /opt/ros/$ROS_DISTRO/share/realsense_navigation diff --git a/ros-realsense-nav/turtlebot/launch/amcl.launch b/ros-realsense-nav/turtlebot/launch/amcl.launch new file mode 100644 index 0000000000..8ca1b72d90 --- /dev/null +++ b/ros-realsense-nav/turtlebot/launch/amcl.launch @@ -0,0 +1,78 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ros-realsense-nav/turtlebot/launch/gmapping.launch b/ros-realsense-nav/turtlebot/launch/gmapping.launch new file mode 100644 index 0000000000..7a306641ce --- /dev/null +++ b/ros-realsense-nav/turtlebot/launch/gmapping.launch @@ -0,0 +1,59 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ros-realsense-nav/turtlebot/launch/navigation_demo.launch b/ros-realsense-nav/turtlebot/launch/navigation_demo.launch new file mode 100644 index 0000000000..bcef81f963 --- /dev/null +++ b/ros-realsense-nav/turtlebot/launch/navigation_demo.launch @@ -0,0 +1,40 @@ + + + + + + + + + + + + + + + + + + + + + diff --git a/ros-realsense-nav/turtlebot/launch/realsense_robot_description.launch b/ros-realsense-nav/turtlebot/launch/realsense_robot_description.launch new file mode 100644 index 0000000000..575a5a50f7 --- /dev/null +++ b/ros-realsense-nav/turtlebot/launch/realsense_robot_description.launch @@ -0,0 +1,14 @@ + + + + + + + + + + + + diff --git a/ros-realsense-nav/turtlebot/launch/simulate_mapping.launch b/ros-realsense-nav/turtlebot/launch/simulate_mapping.launch new file mode 100644 index 0000000000..c6bcc076a9 --- /dev/null +++ b/ros-realsense-nav/turtlebot/launch/simulate_mapping.launch @@ -0,0 +1,55 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ros-realsense-nav/turtlebot/package.xml b/ros-realsense-nav/turtlebot/package.xml new file mode 100644 index 0000000000..86d6eab394 --- /dev/null +++ b/ros-realsense-nav/turtlebot/package.xml @@ -0,0 +1,22 @@ + + + realsense_navigation + 0.0.1 + Intel(r) RealSense(tm) Technology package allowing the use of the R200 camera with the navigation stack + + Amit Moran + + See license attached. + + https://github.com/PercATI/RealSense-ROS + + Amit Moran + + catkin + roscpp + rospy + + roscpp + rospy + + diff --git a/ros-realsense-nav/turtlebot/robot_description/custom_costmap_params.yaml b/ros-realsense-nav/turtlebot/robot_description/custom_costmap_params.yaml new file mode 100644 index 0000000000..b89cdd26cc --- /dev/null +++ b/ros-realsense-nav/turtlebot/robot_description/custom_costmap_params.yaml @@ -0,0 +1,24 @@ +global_costmap: + robot_radius: 0.20 # distance a circular robot should be clear of the obstacle (kobuki: 0.18) + obstacle_layer: + scan: + data_type: LaserScan + topic: scan + marking: true + clearing: true + min_obstacle_height: 0.05 # previous: 0.25, too high for the DS4 configuration! + max_obstacle_height: 0.35 + +local_costmap: + robot_radius: 0.18 # distance a circular robot should be clear of the obstacle (kobuki: 0.18) + obstacle_layer: + scan: + data_type: LaserScan + topic: scan + marking: true + clearing: true + min_obstacle_height: 0.05 # previous: 0.25, too high for the DS4 configuration! + max_obstacle_height: 0.35 + + + diff --git a/ros-realsense-nav/turtlebot/robot_description/kobuki_minimal_r200.urdf.xacro b/ros-realsense-nav/turtlebot/robot_description/kobuki_minimal_r200.urdf.xacro new file mode 100644 index 0000000000..662294778b --- /dev/null +++ b/ros-realsense-nav/turtlebot/robot_description/kobuki_minimal_r200.urdf.xacro @@ -0,0 +1,14 @@ + + + + + + + + + + \ No newline at end of file diff --git a/ros-realsense-nav/turtlebot/robot_description/meshes/sensors/r200.dae b/ros-realsense-nav/turtlebot/robot_description/meshes/sensors/r200.dae new file mode 100644 index 0000000000..c1ebc6ab21 --- /dev/null +++ b/ros-realsense-nav/turtlebot/robot_description/meshes/sensors/r200.dae @@ -0,0 +1,890 @@ + + + + + Google SketchUp 8.0.4811 + + 2015-05-31T08:41:34Z + 2015-05-31T08:41:34Z + + Z_UP + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 0.1184986753859656 7.755517072645532 2.24409448818898 51.06260368681876 7.755517072645532 2.165354330708662 0.1184986753859656 7.755517072645532 2.165354330708662 51.06260368681876 7.755517072645532 2.24409448818898 0.1184986753859656 7.755517072645532 2.24409448818898 0.1184986753859656 2.804370064010866 2.165354330708662 0.1184986753859656 2.804370064010866 2.24409448818898 0.1184986753859656 7.755517072645532 2.165354330708662 51.06260368681876 7.755517072645532 2.165354330708662 51.06260368681876 0.1184986753859656 2.24409448818898 51.06260368681876 0.1184986753859656 2.165354330708662 51.06260368681876 7.755517072645532 2.24409448818898 25.61991398185795 2.804370064010866 2.24409448818898 0.1184986753859656 2.804370064010866 2.165354330708662 25.61991398185795 2.804370064010866 2.165354330708662 0.1184986753859656 2.804370064010866 2.24409448818898 51.06260368681876 0.1184986753859656 2.24409448818898 30.70679771243117 0.1184986753859656 2.165354330708662 51.06260368681876 0.1184986753859656 2.165354330708662 30.70679771243117 0.1184986753859656 2.24409448818898 30.70679771243117 0.1184986753859656 2.24409448818898 25.61991398185795 2.804370064010866 2.165354330708662 30.70679771243117 0.1184986753859656 2.165354330708662 25.61991398185795 2.804370064010866 2.24409448818898 + + + + + + + + + + 0 1 0 0 1 0 0 1 0 0 1 0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 -1.741429659934826e-017 -1 -0 -1.741429659934826e-017 -1 -0 -1.741429659934826e-017 -1 -0 -1.741429659934826e-017 -1 -0 -1.363521329027796e-018 -1 1.38790518535184e-045 -1.363521329027796e-018 -1 1.38790518535184e-045 -1.363521329027796e-018 -1 1.38790518535184e-045 -1.363521329027796e-018 -1 1.38790518535184e-045 -0.4669118737456303 -0.8843038517135072 -0 -0.4669118737456303 -0.8843038517135072 -0 -0.4669118737456303 -0.8843038517135072 -0 -0.4669118737456303 -0.8843038517135072 -0 + + + + + + + + + + + + + + +

0 1 2 1 0 3 4 5 6 5 4 7 8 9 10 9 8 11 12 13 14 13 12 15 16 17 18 17 16 19 20 21 22 21 20 23

+ + + + + + + 0.1184986753859656 2.43930318405221 1.968503937007876 0.1184986753859656 0.2465682045726894 2.165354330708662 0.1184986753859656 0.2465682045726894 1.968503937007876 0.1184986753859656 2.43930318405221 2.165354330708662 0.1184986753859656 0.2465682045726894 1.968503937007876 0.119594327961949 0.2298517765885317 2.165354330708662 0.119594327961949 0.2298517765885317 1.968503937007876 0.1184986753859656 0.2465682045726894 2.165354330708662 0.2465682045726913 0.1184986753859656 1.968503937007876 0.3477764914940549 0.5226027736765067 1.968503937007876 0.3460392041832313 0.5491086559751139 1.968503937007876 0.352958627958972 0.4965504143728474 1.968503937007876 0.361496945786306 0.4713973411548998 1.968503937007876 0.3732453519907644 0.4475739300791728 1.968503937007876 0.3880028280849136 0.4254878063142707 1.968503937007876 0.4055168695612388 0.4055168695612393 1.968503937007876 0.4254878063142707 0.3880028280849154 1.968503937007876 0.4475739300791731 0.3732453519907652 1.968503937007876 0.4713973411549005 0.3614969457863064 1.968503937007876 0.4965504143728469 0.3529586279589738 1.968503937007876 0.5226027736765072 0.3477764914940557 1.968503937007876 0.5491086559751147 0.346039204183232 1.968503937007876 30.0860261920037 0.1184986753859688 1.968503937007876 28.98669970978262 0.3460392041831966 1.968503937007876 29.00270410638306 0.3478174866438403 1.968503937007876 29.01792778668387 0.3530655869813785 1.968503937007876 29.03162811879157 0.3615274957018001 1.968503937007876 29.04313678181573 0.3727904293538459 1.968503937007876 29.05189236747371 0.386304966668887 1.968503937007876 29.05746776635262 0.4014118500799385 1.968503937007876 29.05959100288907 0.4173741452051467 1.968503937007876 0.119594327961949 0.2298517765885317 1.968503937007876 0.1184986753859656 2.43930318405221 1.968503937007876 0.1184986753859656 0.2465682045726894 1.968503937007876 0.1195943279619488 2.456019612036368 1.968503937007876 0.1228625387705512 2.472450017303047 1.968503937007876 0.1228625387705518 0.2134213713218521 1.968503937007876 0.1282473878187184 2.488313271062767 1.968503937007876 0.1282473878187189 0.1975581175621329 1.968503937007876 0.1356567388462739 2.503337948645572 1.968503937007876 0.1356567388462747 0.1825334399793274 1.968503937007876 0.1449638158028762 2.517266973652394 1.968503937007876 0.1449638158028776 0.1686044149725052 1.968503937007876 0.1560093720213884 2.529862016603511 1.968503937007876 0.1560093720213896 0.1560093720213882 1.968503937007876 0.1686044149725052 2.540907572822023 1.968503937007876 0.1686044149725068 0.1449638158028763 1.968503937007876 0.1825334399793273 2.550214649778626 1.968503937007876 0.1825334399793289 0.1356567388462739 1.968503937007876 0.1975581175621327 2.557624000806182 1.968503937007876 0.197558117562134 0.1282473878187185 1.968503937007876 0.213421371321852 2.563008849854349 1.968503937007876 0.2134213713218537 0.1228625387705514 1.968503937007876 0.2298517765885315 2.566277060662952 1.968503937007876 0.2298517765885331 0.1195943279619491 1.968503937007876 0.2465682045726894 2.567372713238935 1.968503937007876 0.3460392041832319 2.136762732649793 1.968503937007876 0.3477764914940558 2.163268614948401 1.968503937007876 0.3529586279589722 2.189320974252061 1.968503937007876 0.3614969457863068 2.214474047470008 1.968503937007876 0.3732453519907648 2.238297458545735 1.968503937007876 0.3880028280849145 2.260383582310638 1.968503937007876 0.4055168695612396 2.280354519063669 1.968503937007876 0.4254878063142705 2.297868560539994 1.968503937007876 0.4475739300791732 2.312626036634144 1.968503937007876 0.4713973411548998 2.324374442838602 1.968503937007876 0.4965504143728471 2.332912760665936 1.968503937007876 0.5226027736765068 2.338094897130853 1.968503937007876 0.5491086559751146 2.339832184441677 1.968503937007876 25.56118838034679 2.567372713238936 1.968503937007876 25.50480608586854 2.339832184441669 1.968503937007876 29.0207414471994 0.4834205400204281 1.968503937007876 30.09912146437194 0.1713469183847506 1.968503937007876 29.03406389556177 0.4743753551861666 1.968503937007876 29.04507585432682 0.4626263227489491 1.968503937007876 29.05324014512329 0.4487465765392888 1.968503937007876 29.05815850270828 0.4334131895122746 1.968503937007876 30.09803909744245 0.1212016043046447 1.968503937007876 30.10330938016302 0.1244567554178949 1.968503937007876 30.10848249331568 0.1633477397435226 1.968503937007876 30.10773656538716 0.1287894127682915 1.968503937007876 30.11110468898 0.1339882234195986 1.968503937007876 30.11162315591949 0.1580084394959358 1.968503937007876 30.11324944927784 0.1397995822959414 1.968503937007876 30.11351516370367 0.1521099485644012 1.968503937007876 30.11406622194742 0.145940003383379 1.968503937007876 0.1195943279619488 2.456019612036368 1.968503937007876 0.1184986753859656 2.43930318405221 2.165354330708662 0.1184986753859656 2.43930318405221 1.968503937007876 0.1195943279619488 2.456019612036368 2.165354330708662 0.1228625387705518 0.2134213713218521 2.165354330708662 0.1228625387705518 0.2134213713218521 1.968503937007876 30.09912146437194 0.1713469183847506 2.165354330708662 25.56118838034679 2.567372713238936 1.968503937007876 30.09912146437194 0.1713469183847506 1.968503937007876 25.56118838034679 2.567372713238936 2.165354330708662 25.56118838034679 2.567372713238936 2.165354330708662 0.2465682045726894 2.567372713238935 1.968503937007876 25.56118838034679 2.567372713238936 1.968503937007876 0.2465682045726894 2.567372713238935 2.165354330708662 0.2465682045726894 2.567372713238935 2.165354330708662 0.2298517765885315 2.566277060662952 1.968503937007876 0.2465682045726894 2.567372713238935 1.968503937007876 0.2298517765885315 2.566277060662952 2.165354330708662 0.213421371321852 2.563008849854349 1.968503937007876 0.213421371321852 2.563008849854349 2.165354330708662 0.1975581175621327 2.557624000806182 1.968503937007876 0.1975581175621327 2.557624000806182 2.165354330708662 0.1825334399793273 2.550214649778626 1.968503937007876 0.1825334399793273 2.550214649778626 2.165354330708662 0.1686044149725052 2.540907572822023 1.968503937007876 0.1686044149725052 2.540907572822023 2.165354330708662 0.1560093720213884 2.529862016603511 1.968503937007876 0.1560093720213884 2.529862016603511 2.165354330708662 0.1449638158028762 2.517266973652394 2.165354330708662 0.1449638158028762 2.517266973652394 1.968503937007876 0.1356567388462739 2.503337948645572 2.165354330708662 0.1356567388462739 2.503337948645572 1.968503937007876 0.1282473878187184 2.488313271062767 2.165354330708662 0.1282473878187184 2.488313271062767 1.968503937007876 0.1228625387705512 2.472450017303047 2.165354330708662 0.1228625387705512 2.472450017303047 1.968503937007876 0.1282473878187189 0.1975581175621329 2.165354330708662 0.1282473878187189 0.1975581175621329 1.968503937007876 0.1356567388462747 0.1825334399793274 2.165354330708662 0.1356567388462747 0.1825334399793274 1.968503937007876 0.1449638158028776 0.1686044149725052 2.165354330708662 0.1449638158028776 0.1686044149725052 1.968503937007876 0.1560093720213896 0.1560093720213882 2.165354330708662 0.1560093720213896 0.1560093720213882 1.968503937007876 0.1686044149725068 0.1449638158028763 1.968503937007876 0.1686044149725068 0.1449638158028763 2.165354330708662 0.1825334399793289 0.1356567388462739 1.968503937007876 0.1825334399793289 0.1356567388462739 2.165354330708662 0.197558117562134 0.1282473878187185 1.968503937007876 0.197558117562134 0.1282473878187185 2.165354330708662 0.2134213713218537 0.1228625387705514 1.968503937007876 0.2134213713218537 0.1228625387705514 2.165354330708662 0.2298517765885331 0.1195943279619491 1.968503937007876 0.2298517765885331 0.1195943279619491 2.165354330708662 0.2465682045726913 0.1184986753859656 1.968503937007876 0.2465682045726913 0.1184986753859656 2.165354330708662 0.2465682045726913 0.1184986753859656 2.165354330708662 30.0860261920037 0.1184986753859688 1.968503937007876 0.2465682045726913 0.1184986753859656 1.968503937007876 30.0860261920037 0.1184986753859688 2.165354330708662 30.0860261920037 0.1184986753859688 2.165354330708662 30.09803909744245 0.1212016043046447 1.968503937007876 30.0860261920037 0.1184986753859688 1.968503937007876 30.09803909744245 0.1212016043046447 2.165354330708662 30.09803909744245 0.1212016043046447 2.165354330708662 30.10330938016302 0.1244567554178949 1.968503937007876 30.09803909744245 0.1212016043046447 1.968503937007876 30.10330938016302 0.1244567554178949 2.165354330708662 30.10330938016302 0.1244567554178949 2.165354330708662 30.10773656538716 0.1287894127682915 1.968503937007876 30.10330938016302 0.1244567554178949 1.968503937007876 30.10773656538716 0.1287894127682915 2.165354330708662 30.11110468898 0.1339882234195986 2.165354330708662 30.10773656538716 0.1287894127682915 1.968503937007876 30.10773656538716 0.1287894127682915 2.165354330708662 30.11110468898 0.1339882234195986 1.968503937007876 30.11324944927784 0.1397995822959414 2.165354330708662 30.11110468898 0.1339882234195986 1.968503937007876 30.11110468898 0.1339882234195986 2.165354330708662 30.11324944927784 0.1397995822959414 1.968503937007876 30.11406622194742 0.145940003383379 2.165354330708662 30.11324944927784 0.1397995822959414 1.968503937007876 30.11324944927784 0.1397995822959414 2.165354330708662 30.11406622194742 0.145940003383379 1.968503937007876 30.11351516370367 0.1521099485644012 2.165354330708662 30.11406622194742 0.145940003383379 1.968503937007876 30.11406622194742 0.145940003383379 2.165354330708662 30.11351516370367 0.1521099485644012 1.968503937007876 30.11162315591949 0.1580084394959358 2.165354330708662 30.11351516370367 0.1521099485644012 1.968503937007876 30.11351516370367 0.1521099485644012 2.165354330708662 30.11162315591949 0.1580084394959358 1.968503937007876 30.10848249331568 0.1633477397435226 2.165354330708662 30.11162315591949 0.1580084394959358 1.968503937007876 30.11162315591949 0.1580084394959358 2.165354330708662 30.10848249331568 0.1633477397435226 1.968503937007876 30.10848249331568 0.1633477397435226 2.165354330708662 30.09912146437194 0.1713469183847506 1.968503937007876 30.10848249331568 0.1633477397435226 1.968503937007876 30.09912146437194 0.1713469183847506 2.165354330708662 + + + + + + + + + + 1 0 0 1 0 0 1 0 0 1 0 0 0.9978589232386028 0.06540312923015378 0 0.9914448613738085 0.1305261922200654 0 0.9914448613738085 0.1305261922200654 0 0.9978589232386028 0.06540312923015378 0 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 0.9914448613738105 -0.1305261922200504 0 0.9978589232386037 -0.06540312923014092 -0 0.9978589232386037 -0.06540312923014092 -0 0.9914448613738105 -0.1305261922200504 0 0.9659258262890664 0.2588190451025282 0 0.9659258262890664 0.2588190451025282 0 -0.4669118737456304 -0.8843038517135073 0 -0.4669118737456304 -0.8843038517135073 0 -0.4669118737456304 -0.8843038517135073 0 -0.4669118737456304 -0.8843038517135073 0 3.508559139078474e-017 -1 -0 3.508559139078474e-017 -1 -0 3.508559139078474e-017 -1 -0 3.508559139078474e-017 -1 -0 0.06540312923014653 -0.9978589232386035 -0 0.1305261922200657 -0.9914448613738085 0 0.06540312923014653 -0.9978589232386035 -0 0.1305261922200657 -0.9914448613738085 0 0.2588190451025326 -0.9659258262890651 0 0.2588190451025326 -0.9659258262890651 0 0.3826834323650984 -0.9238795325112833 0 0.3826834323650984 -0.9238795325112833 0 0.5000000000000157 -0.8660254037844295 0 0.5000000000000157 -0.8660254037844295 0 0.6087614290087283 -0.7933533402912294 0 0.6087614290087283 -0.7933533402912294 0 0.7071067811865515 -0.7071067811865435 0 0.7071067811865515 -0.7071067811865435 0 0.7933533402912371 -0.6087614290087183 0 0.7933533402912371 -0.6087614290087183 0 0.8660254037844378 -0.5000000000000014 0 0.8660254037844378 -0.5000000000000014 0 0.9238795325112877 -0.3826834323650871 0 0.9238795325112877 -0.3826834323650871 0 0.965925826289069 -0.258819045102518 0 0.965925826289069 -0.258819045102518 0 0.9238795325112841 0.3826834323650963 0 0.9238795325112841 0.3826834323650963 0 0.8660254037844283 0.500000000000018 0 0.8660254037844283 0.500000000000018 0 0.7933533402912328 0.6087614290087237 0 0.7933533402912328 0.6087614290087237 0 0.7071067811865434 0.7071067811865516 0 0.7071067811865434 0.7071067811865516 0 0.6087614290087107 0.7933533402912428 0 0.6087614290087107 0.7933533402912428 0 0.5000000000000019 0.8660254037844377 0 0.5000000000000019 0.8660254037844377 0 0.3826834323650855 0.9238795325112886 0 0.3826834323650855 0.9238795325112886 0 0.2588190451025133 0.9659258262890702 0 0.2588190451025133 0.9659258262890702 0 0.1305261922200561 0.9914448613738098 0 0.1305261922200561 0.9914448613738098 0 0.06540312923015844 0.9978589232386027 0 0.06540312923015844 0.9978589232386027 0 -1.083146562226566e-016 1 -1.259049816913602e-017 -1.083146562226566e-016 1 -1.259049816913602e-017 -1.083146562226566e-016 1 -1.259049816913602e-017 -1.083146562226566e-016 1 -1.259049816913602e-017 -0.2195141426946766 0.9756093178916556 -0 -0.2195141426946766 0.9756093178916556 -0 -0.2195141426946766 0.9756093178916556 -0 -0.2195141426946766 0.9756093178916556 -0 -0.5254901336654482 0.8507996940645135 -0 -0.5254901336654482 0.8507996940645135 -0 -0.5254901336654482 0.8507996940645135 -0 -0.5254901336654482 0.8507996940645135 -0 -0.6994356363115606 0.7146955930026729 -0 -0.6994356363115606 0.7146955930026729 -0 -0.6994356363115606 0.7146955930026729 -0 -0.6994356363115606 0.7146955930026729 -0 -0.8392617144369261 0.5437276659140966 -0 -0.8392617144369261 0.5437276659140966 -0 -0.8392617144369261 0.5437276659140966 -0 -0.8392617144369261 0.5437276659140966 -0 -0.9381474611967006 0.3462359615207312 -0 -0.9381474611967006 0.3462359615207312 -0 -0.9381474611967006 0.3462359615207312 -0 -0.9381474611967006 0.3462359615207312 -0 -0.9912690949632644 0.1318543945824739 -0 -0.9912690949632644 0.1318543945824739 -0 -0.9912690949632644 0.1318543945824739 -0 -0.9912690949632644 0.1318543945824739 -0 -0.9960352699715455 -0.08895920960030257 -0 -0.9960352699715455 -0.08895920960030257 -0 -0.9960352699715455 -0.08895920960030257 -0 -0.9960352699715455 -0.08895920960030257 -0 -0.9522134857026214 -0.3054332621802407 -0 -0.9522134857026214 -0.3054332621802407 -0 -0.9522134857026214 -0.3054332621802407 -0 -0.9522134857026214 -0.3054332621802407 -0 -0.8619414285757618 -0.5070078635531948 -0 -0.8619414285757618 -0.5070078635531948 -0 -0.8619414285757618 -0.5070078635531948 -0 -0.8619414285757618 -0.5070078635531948 -0 -0.6496407765509248 -0.7602413178999887 -0 -0.6496407765509248 -0.7602413178999887 -0 -0.6496407765509248 -0.7602413178999887 -0 -0.6496407765509248 -0.7602413178999887 -0 + + + + + + + + + + + + + + +

0 1 2 1 0 3 4 5 6 5 4 7 8 9 10 9 8 11 11 8 12 12 8 13 13 8 14 14 8 15 15 8 16 16 8 17 17 8 18 18 8 19 19 8 20 20 8 21 21 8 22 21 22 23 23 22 24 24 22 25 25 22 26 26 22 27 27 22 28 28 22 29 29 22 30 31 32 33 32 31 34 34 31 35 35 31 36 35 36 37 37 36 38 37 38 39 39 38 40 39 40 41 41 40 42 41 42 43 43 42 44 43 44 45 45 44 46 45 46 47 47 46 48 47 48 49 49 48 50 49 50 51 51 50 52 51 52 53 53 52 54 53 54 55 55 54 8 55 8 56 55 56 57 55 57 58 55 58 59 55 59 60 55 60 61 55 61 62 55 62 63 55 63 64 55 64 65 55 65 66 55 66 67 55 67 68 55 68 69 56 8 10 69 68 70 69 70 71 69 71 72 72 71 73 72 73 74 72 74 75 72 75 76 72 76 30 72 30 22 72 22 77 72 77 78 72 78 79 79 78 80 79 80 81 79 81 82 82 81 83 82 83 84 84 83 85 86 87 88 87 86 89 6 90 91 90 6 5 92 93 94 93 92 95 96 97 98 97 96 99 100 101 102 101 100 103 103 104 101 104 103 105 105 106 104 106 105 107 107 108 106 108 107 109 109 110 108 110 109 111 111 112 110 112 111 113 112 114 115 114 112 113 115 116 117 116 115 114 117 118 119 118 117 116 119 120 121 120 119 118 121 89 86 89 121 120 91 122 123 122 91 90 123 124 125 124 123 122 125 126 127 126 125 124 127 128 129 128 127 126 128 130 129 130 128 131 131 132 130 132 131 133 133 134 132 134 133 135 135 136 134 136 135 137 137 138 136 138 137 139 139 140 138 140 139 141 142 143 144 143 142 145 146 147 148 147 146 149 150 151 152 151 150 153 154 155 156 155 154 157 158 159 160 159 158 161 162 163 164 163 162 165 166 167 168 167 166 169 170 171 172 171 170 173 174 175 176 175 174 177 178 179 180 179 178 181 182 183 184 183 182 185

+
+
+
+ + + + 29.00270410638306 0.3478174866438403 1.968503937007876 29.01792778668387 0.3530655869813785 1.062992125984253 29.00270410638306 0.3478174866438403 1.062992125984253 29.01792778668387 0.3530655869813785 1.968503937007876 28.98669970978262 0.3460392041831966 1.968503937007876 29.00270410638306 0.3478174866438403 1.110223024625157e-015 28.98669970978262 0.3460392041831966 1.110223024625157e-015 29.03162811879157 0.3615274957018001 1.062992125984253 29.03162811879157 0.3615274957018001 1.968503937007876 43.19998259988454 2.339832184441669 1.062992125984254 29.0207414471994 0.4834205400204281 1.062992125984253 25.50480608586854 2.339832184441669 1.062992125984253 29.03406389556177 0.4743753551861666 1.062992125984253 29.04507585432682 0.4626263227489491 1.062992125984253 29.05324014512329 0.4487465765392888 1.062992125984253 29.05815850270828 0.4334131895122746 1.062992125984253 29.05959100288907 0.4173741452051467 1.062992125984253 43.1999825998845 0.3478174866438403 1.062992125984253 43.22648848218315 0.3495547739546886 1.062992125984253 43.22648848218314 2.338094897130838 1.062992125984254 43.25254084148678 2.332912760665932 1.062992125984254 43.25254084148678 0.3547369104195798 1.062992125984253 43.27769391470476 2.324374442838592 1.062992125984254 43.27769391470472 0.3632752282469342 1.062992125984253 43.30151732578045 0.3750236344513948 1.062992125984253 43.30151732578047 2.312626036634134 1.062992125984254 43.32360344954538 0.3897811105455223 1.062992125984253 43.32360344954538 2.297868560539985 1.062992125984254 43.34357438629841 2.280354519063661 1.062992125984254 43.34357438629839 0.4072951520218343 1.062992125984253 43.36108842777473 0.4272660887748755 1.062992125984253 43.36108842777473 2.260383582310626 1.062992125984254 43.37584590386888 2.238297458545732 1.062992125984254 43.37584590386889 0.4493522125397943 1.062992125984253 43.38759431007334 2.214474047469995 1.062992125984254 43.38759431007329 0.4731756236155132 1.062992125984253 43.39613262790066 0.4983286968334623 1.062992125984253 43.39613262790067 2.189320974252053 1.062992125984254 43.40131476436558 0.5243810561371171 1.062992125984253 43.40131476436559 2.163268614948387 1.062992125984254 43.4030520516764 0.5508869384357514 1.062992125984253 43.4030520516764 2.136762732649783 1.062992125984254 29.01792778668387 0.3530655869813785 1.062992125984253 29.00270410638306 0.3478174866438403 1.062992125984253 29.03162811879157 0.3615274957018001 1.062992125984253 29.04313678181573 0.3727904293538459 1.062992125984253 29.05189236747371 0.386304966668887 1.062992125984253 29.05746776635262 0.4014118500799385 1.062992125984253 0.5491086559751147 0.346039204183232 1.968503937007876 28.98669970978262 0.3460392041831966 1.110223024625157e-015 0.5491086559751147 0.346039204183232 1.110223024625157e-015 28.98669970978262 0.3460392041831966 1.968503937007876 29.00270410638306 0.3478174866438403 1.110223024625157e-015 43.1999825998845 0.3478174866438403 0.157480314960631 50.14425631911605 0.3478174866438403 1.110223024625157e-015 29.00270410638306 0.3478174866438403 1.062992125984253 43.1999825998845 0.3478174866438403 1.062992125984253 50.14425631911605 0.3478174866438403 0.157480314960631 29.04313678181573 0.3727904293538459 1.062992125984253 29.04313678181573 0.3727904293538459 1.968503937007876 43.4030520516764 2.136762732649783 1.062992125984254 43.4030520516764 0.5508869384357514 0.157480314960631 43.4030520516764 0.5508869384357514 1.062992125984253 43.4030520516764 2.136762732649783 0.1574803149606311 43.4030520516764 0.5508869384357514 1.062992125984253 43.40131476436558 0.5243810561371171 0.157480314960631 43.40131476436558 0.5243810561371171 1.062992125984253 43.4030520516764 0.5508869384357514 0.157480314960631 43.39613262790066 0.4983286968334623 0.157480314960631 43.39613262790066 0.4983286968334623 1.062992125984253 43.38759431007329 0.4731756236155132 0.157480314960631 43.38759431007329 0.4731756236155132 1.062992125984253 43.37584590386889 0.4493522125397943 0.157480314960631 43.37584590386889 0.4493522125397943 1.062992125984253 43.36108842777473 0.4272660887748755 0.157480314960631 43.36108842777473 0.4272660887748755 1.062992125984253 43.34357438629839 0.4072951520218343 0.157480314960631 43.34357438629839 0.4072951520218343 1.062992125984253 43.32360344954538 0.3897811105455223 1.062992125984253 43.32360344954538 0.3897811105455223 0.157480314960631 43.30151732578045 0.3750236344513948 1.062992125984253 43.30151732578045 0.3750236344513948 0.157480314960631 43.27769391470472 0.3632752282469342 1.062992125984253 43.27769391470472 0.3632752282469342 0.157480314960631 43.25254084148678 0.3547369104195798 1.062992125984253 43.25254084148678 0.3547369104195798 0.157480314960631 43.22648848218315 0.3495547739546886 1.062992125984253 43.22648848218315 0.3495547739546886 0.157480314960631 43.1999825998845 0.3478174866438403 1.062992125984253 43.1999825998845 0.3478174866438403 0.157480314960631 29.05189236747371 0.386304966668887 1.968503937007876 29.05189236747371 0.386304966668887 1.062992125984253 29.05746776635262 0.4014118500799385 1.968503937007876 29.05746776635262 0.4014118500799385 1.062992125984253 29.05959100288907 0.4173741452051467 1.968503937007876 29.05959100288907 0.4173741452051467 1.062992125984253 29.05815850270828 0.4334131895122746 1.968503937007876 29.05815850270828 0.4334131895122746 1.062992125984253 29.05324014512329 0.4487465765392888 1.968503937007876 29.05324014512329 0.4487465765392888 1.062992125984253 29.04507585432682 0.4626263227489491 1.968503937007876 29.04507585432682 0.4626263227489491 1.062992125984253 29.03406389556177 0.4743753551861666 1.968503937007876 29.03406389556177 0.4743753551861666 1.062992125984253 29.0207414471994 0.4834205400204281 1.062992125984253 29.0207414471994 0.4834205400204281 1.968503937007876 29.0207414471994 0.4834205400204281 1.968503937007876 25.50480608586854 2.339832184441669 1.062992125984253 29.0207414471994 0.4834205400204281 1.062992125984253 25.50480608586854 2.339832184441669 1.968503937007876 50.14425631911605 2.339832184441669 0.157480314960631 25.50480608586854 2.339832184441669 1.110223024625157e-015 50.14425631911605 2.339832184441669 1.110223024625157e-015 43.19998259988454 2.339832184441669 0.1574803149606311 25.50480608586854 2.339832184441669 1.062992125984253 43.19998259988454 2.339832184441669 1.062992125984254 43.22648848218314 2.338094897130838 1.062992125984254 43.19998259988454 2.339832184441669 0.1574803149606311 43.22648848218314 2.338094897130838 0.1574803149606311 43.19998259988454 2.339832184441669 1.062992125984254 43.25254084148678 2.332912760665932 1.062992125984254 43.25254084148678 2.332912760665932 0.1574803149606311 43.27769391470476 2.324374442838592 1.062992125984254 43.27769391470476 2.324374442838592 0.1574803149606311 43.30151732578047 2.312626036634134 1.062992125984254 43.30151732578047 2.312626036634134 0.1574803149606311 43.32360344954538 2.297868560539985 1.062992125984254 43.32360344954538 2.297868560539985 0.1574803149606311 43.34357438629841 2.280354519063661 1.062992125984254 43.34357438629841 2.280354519063661 0.1574803149606311 43.36108842777473 2.260383582310626 0.1574803149606311 43.36108842777473 2.260383582310626 1.062992125984254 43.37584590386888 2.238297458545732 0.1574803149606311 43.37584590386888 2.238297458545732 1.062992125984254 43.38759431007334 2.214474047469995 0.1574803149606311 43.38759431007334 2.214474047469995 1.062992125984254 43.39613262790067 2.189320974252053 0.1574803149606311 43.39613262790067 2.189320974252053 1.062992125984254 43.40131476436559 2.163268614948387 0.1574803149606311 43.40131476436559 2.163268614948387 1.062992125984254 43.4030520516764 2.136762732649783 0.1574803149606311 43.4030520516764 2.136762732649783 1.062992125984254 0.5226027736765072 0.3477764914940557 1.968503937007876 0.5491086559751147 0.346039204183232 1.110223024625157e-015 0.5226027736765072 0.3477764914940557 1.110223024625157e-015 0.5491086559751147 0.346039204183232 1.968503937007876 50.14425631911605 2.339832184441669 0.157480314960631 43.22648848218314 2.338094897130838 0.1574803149606311 43.19998259988454 2.339832184441669 0.1574803149606311 43.25254084148678 2.332912760665932 0.1574803149606311 43.27769391470476 2.324374442838592 0.1574803149606311 43.30151732578047 2.312626036634134 0.1574803149606311 43.32360344954538 2.297868560539985 0.1574803149606311 43.34357438629841 2.280354519063661 0.1574803149606311 43.36108842777473 2.260383582310626 0.1574803149606311 43.37584590386888 2.238297458545732 0.1574803149606311 43.38759431007334 2.214474047469995 0.1574803149606311 43.39613262790067 2.189320974252053 0.1574803149606311 43.40131476436559 2.163268614948387 0.1574803149606311 43.4030520516764 2.136762732649783 0.1574803149606311 43.4030520516764 0.5508869384357514 0.157480314960631 43.22648848218315 0.3495547739546886 0.157480314960631 50.14425631911605 0.3478174866438403 0.157480314960631 43.1999825998845 0.3478174866438403 0.157480314960631 43.25254084148678 0.3547369104195798 0.157480314960631 43.27769391470472 0.3632752282469342 0.157480314960631 43.30151732578045 0.3750236344513948 0.157480314960631 43.32360344954538 0.3897811105455223 0.157480314960631 43.34357438629839 0.4072951520218343 0.157480314960631 43.36108842777473 0.4272660887748755 0.157480314960631 43.37584590386889 0.4493522125397943 0.157480314960631 43.38759431007329 0.4731756236155132 0.157480314960631 43.39613262790066 0.4983286968334623 0.157480314960631 43.40131476436558 0.5243810561371171 0.157480314960631 50.17076220141468 2.338094897130827 0.157480314960631 50.17076220141466 0.3495547739546495 0.157480314960631 50.19681456071831 0.35473691041958 0.157480314960631 50.19681456071832 2.332912760665919 0.157480314960631 50.22196763393623 0.3632752282469015 0.157480314960631 50.22196763393626 2.324374442838587 0.157480314960631 50.24579104501201 0.3750236344513794 0.157480314960631 50.24579104501199 2.312626036634129 0.157480314960631 50.26787716877689 2.297868560539985 0.157480314960631 50.26787716877686 0.3897811105455421 0.157480314960631 50.28784810552991 0.407295152021843 0.157480314960631 50.28784810552993 2.280354519063654 0.157480314960631 50.30536214700624 0.4272660887748815 0.157480314960631 50.30536214700626 2.260383582310614 0.157480314960631 50.32011962310041 0.4493522125397739 0.157480314960631 50.32011962310039 2.238297458545719 0.157480314960631 50.33186802930484 2.214474047469999 0.157480314960631 50.33186802930485 0.4731756236154915 0.157480314960631 50.34040634713219 2.189320974252057 0.157480314960631 50.3404063471322 0.498328696833425 0.157480314960631 50.34558848359709 2.163268614948385 0.157480314960631 50.34558848359711 0.5243810561371139 0.157480314960631 50.3473257709079 2.136762732649773 0.157480314960631 50.3473257709079 0.5508869384357039 0.157480314960631 50.14425631911605 0.3478174866438403 0.157480314960631 50.17076220141466 0.3495547739546495 1.110223024625157e-015 50.14425631911605 0.3478174866438403 1.110223024625157e-015 50.17076220141466 0.3495547739546495 0.157480314960631 25.50480608586854 2.339832184441669 1.062992125984253 0.5491086559751146 2.339832184441677 1.110223024625157e-015 25.50480608586854 2.339832184441669 1.110223024625157e-015 0.5491086559751146 2.339832184441677 1.968503937007876 25.50480608586854 2.339832184441669 1.968503937007876 50.17076220141468 2.338094897130827 0.157480314960631 50.14425631911605 2.339832184441669 1.110223024625157e-015 50.17076220141468 2.338094897130827 1.110223024625157e-015 50.14425631911605 2.339832184441669 0.157480314960631 0.4965504143728469 0.3529586279589738 1.968503937007876 0.4965504143728469 0.3529586279589738 1.110223024625157e-015 50.19681456071832 2.332912760665919 0.157480314960631 50.19681456071832 2.332912760665919 1.110223024625157e-015 50.22196763393626 2.324374442838587 0.157480314960631 50.22196763393626 2.324374442838587 1.110223024625157e-015 50.24579104501199 2.312626036634129 0.157480314960631 50.24579104501199 2.312626036634129 1.110223024625157e-015 50.26787716877689 2.297868560539985 0.157480314960631 50.26787716877689 2.297868560539985 1.110223024625157e-015 50.28784810552993 2.280354519063654 0.157480314960631 50.28784810552993 2.280354519063654 1.110223024625157e-015 50.30536214700626 2.260383582310614 1.110223024625157e-015 50.30536214700626 2.260383582310614 0.157480314960631 50.32011962310039 2.238297458545719 1.110223024625157e-015 50.32011962310039 2.238297458545719 0.157480314960631 50.33186802930484 2.214474047469999 1.110223024625157e-015 50.33186802930484 2.214474047469999 0.157480314960631 50.34040634713219 2.189320974252057 1.110223024625157e-015 50.34040634713219 2.189320974252057 0.157480314960631 50.34558848359709 2.163268614948385 1.110223024625157e-015 50.34558848359709 2.163268614948385 0.157480314960631 50.3473257709079 2.136762732649773 1.110223024625157e-015 50.3473257709079 2.136762732649773 0.157480314960631 50.3473257709079 2.136762732649773 0.157480314960631 50.3473257709079 0.5508869384357039 1.110223024625157e-015 50.3473257709079 0.5508869384357039 0.157480314960631 50.3473257709079 2.136762732649773 1.110223024625157e-015 50.3473257709079 0.5508869384357039 0.157480314960631 50.34558848359711 0.5243810561371139 1.110223024625157e-015 50.34558848359711 0.5243810561371139 0.157480314960631 50.3473257709079 0.5508869384357039 1.110223024625157e-015 50.3404063471322 0.498328696833425 1.110223024625157e-015 50.3404063471322 0.498328696833425 0.157480314960631 50.33186802930485 0.4731756236154915 1.110223024625157e-015 50.33186802930485 0.4731756236154915 0.157480314960631 50.32011962310041 0.4493522125397739 1.110223024625157e-015 50.32011962310041 0.4493522125397739 0.157480314960631 50.30536214700624 0.4272660887748815 1.110223024625157e-015 50.30536214700624 0.4272660887748815 0.157480314960631 50.28784810552991 0.407295152021843 1.110223024625157e-015 50.28784810552991 0.407295152021843 0.157480314960631 50.26787716877686 0.3897811105455421 0.157480314960631 50.26787716877686 0.3897811105455421 1.110223024625157e-015 50.24579104501201 0.3750236344513794 0.157480314960631 50.24579104501201 0.3750236344513794 1.110223024625157e-015 50.22196763393623 0.3632752282469015 0.157480314960631 50.22196763393623 0.3632752282469015 1.110223024625157e-015 50.19681456071831 0.35473691041958 0.157480314960631 50.19681456071831 0.35473691041958 1.110223024625157e-015 0.5491086559751146 2.339832184441677 1.968503937007876 0.5226027736765068 2.338094897130853 1.110223024625157e-015 0.5491086559751146 2.339832184441677 1.110223024625157e-015 0.5226027736765068 2.338094897130853 1.968503937007876 0.4713973411549005 0.3614969457863064 1.968503937007876 0.4713973411549005 0.3614969457863064 1.110223024625157e-015 0.4965504143728471 2.332912760665936 1.110223024625157e-015 0.4965504143728471 2.332912760665936 1.968503937007876 0.4475739300791731 0.3732453519907652 1.968503937007876 0.4475739300791731 0.3732453519907652 1.110223024625157e-015 0.4713973411548998 2.324374442838602 1.110223024625157e-015 0.4713973411548998 2.324374442838602 1.968503937007876 0.4254878063142707 0.3880028280849154 1.968503937007876 0.4254878063142707 0.3880028280849154 1.110223024625157e-015 0.4475739300791732 2.312626036634144 1.110223024625157e-015 0.4475739300791732 2.312626036634144 1.968503937007876 0.4055168695612388 0.4055168695612393 1.968503937007876 0.4055168695612388 0.4055168695612393 1.110223024625157e-015 0.4254878063142705 2.297868560539994 1.110223024625157e-015 0.4254878063142705 2.297868560539994 1.968503937007876 0.3880028280849136 0.4254878063142707 1.110223024625157e-015 0.3880028280849136 0.4254878063142707 1.968503937007876 0.4055168695612396 2.280354519063669 1.110223024625157e-015 0.4055168695612396 2.280354519063669 1.968503937007876 0.3732453519907644 0.4475739300791728 1.110223024625157e-015 0.3732453519907644 0.4475739300791728 1.968503937007876 0.3880028280849145 2.260383582310638 1.968503937007876 0.3880028280849145 2.260383582310638 1.110223024625157e-015 0.361496945786306 0.4713973411548998 1.110223024625157e-015 0.361496945786306 0.4713973411548998 1.968503937007876 0.3732453519907648 2.238297458545735 1.968503937007876 0.3732453519907648 2.238297458545735 1.110223024625157e-015 0.352958627958972 0.4965504143728474 1.110223024625157e-015 0.352958627958972 0.4965504143728474 1.968503937007876 0.3614969457863068 2.214474047470008 1.968503937007876 0.3614969457863068 2.214474047470008 1.110223024625157e-015 0.3477764914940549 0.5226027736765067 1.110223024625157e-015 0.3477764914940549 0.5226027736765067 1.968503937007876 0.3529586279589722 2.189320974252061 1.968503937007876 0.3529586279589722 2.189320974252061 1.110223024625157e-015 0.3460392041832313 0.5491086559751139 1.110223024625157e-015 0.3460392041832313 0.5491086559751139 1.968503937007876 0.3477764914940558 2.163268614948401 1.968503937007876 0.3477764914940558 2.163268614948401 1.110223024625157e-015 0.3460392041832319 2.136762732649793 1.110223024625157e-015 0.3460392041832313 0.5491086559751139 1.968503937007876 0.3460392041832313 0.5491086559751139 1.110223024625157e-015 0.3460392041832319 2.136762732649793 1.968503937007876 0.3460392041832319 2.136762732649793 1.968503937007876 0.3460392041832319 2.136762732649793 1.110223024625157e-015 + + + + + + + + + + -0.2195141426946883 0.9756093178916528 -2.251662460960872e-031 -0.4283200860438445 0.9036270823140448 -2.039446246926806e-031 -0.1832544872618059 0.983065507938516 -2.276641252136103e-031 -0.4283200860438445 0.9036270823140448 -2.039446246926806e-031 -0.1104325181011955 0.9938836244479679 -2.317022766077274e-031 -0.1104325181011955 0.9938836244479679 -2.317022766077274e-031 -0.1104325181011955 0.9938836244479679 -2.317022766077274e-031 -0.6162319912743373 0.7875646849180484 -1.727743062721139e-031 -0.6162319912743373 0.7875646849180484 -1.727743062721139e-031 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 1.247349874666141e-015 1 -2.354039508393784e-031 1.247349874666141e-015 1 -2.354039508393784e-031 1.247349874666141e-015 1 -2.354039508393784e-031 1.247349874666141e-015 1 -2.354039508393784e-031 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0.7740832592965722 0.6330838077828211 -1.331758214899901e-031 -0.7740832592965722 0.6330838077828211 -1.331758214899901e-031 -1 -5.063450264559819e-035 9.643711856883543e-019 -1 -5.063450264559819e-035 9.643711856883543e-019 -1 -5.063450264559819e-035 9.643711856883543e-019 -1 -5.063450264559819e-035 9.643711856883543e-019 -0.9978589232386242 0.06540312922982872 3.458633610382481e-018 -0.9914448613738267 0.1305261922199271 5.938085634997029e-018 -0.9914448613738267 0.1305261922199271 5.938085634997029e-018 -0.9978589232386242 0.06540312922982872 3.458633610382481e-018 -0.9659258262888851 0.2588190451032043 1.081019779277784e-017 -0.9659258262888851 0.2588190451032043 1.081019779277784e-017 -0.9238795325113519 0.3826834323649326 1.549734446910911e-017 -0.9238795325113519 0.3826834323649326 1.549734446910911e-017 -0.8660254037849143 0.4999999999991764 1.9919327284905e-017 -0.8660254037849143 0.4999999999991764 1.9919327284905e-017 -0.7933533402911954 0.6087614290087726 2.400048488823272e-017 -0.7933533402911954 0.6087614290087726 2.400048488823272e-017 -0.7071067811865249 0.7071067811865701 2.767098754089725e-017 -0.7071067811865249 0.7071067811865701 2.767098754089725e-017 -0.60876142900828 0.7933533402915732 3.086803192490265e-017 -0.60876142900828 0.7933533402915732 3.086803192490265e-017 -0.4999999999994493 0.8660254037847566 3.353691572442538e-017 -0.4999999999994493 0.8660254037847566 3.353691572442538e-017 -0.3826834323655326 0.9238795325111033 3.563197359769641e-017 -0.3826834323655326 0.9238795325111033 3.563197359769641e-017 -0.2588190451025693 0.9659258262890552 3.711735852368559e-017 -0.2588190451025693 0.9659258262890552 3.711735852368559e-017 -0.1305261922200869 0.9914448613738056 3.796765515445271e-017 -0.1305261922200869 0.9914448613738056 3.796765515445271e-017 -0.06540312923095472 0.9978589232385504 3.814966628060576e-017 -0.06540312923095472 0.9978589232385504 3.814966628060576e-017 -0.8941736899130333 0.4477202388404067 -8.708083845489539e-032 -0.8941736899130333 0.4477202388404067 -8.708083845489539e-032 -0.9706451080888319 0.2405162658599619 -3.673793332284476e-032 -0.9706451080888319 0.2405162658599619 -3.673793332284476e-032 -0.9997671337217909 0.02157958131462663 1.539709831518109e-032 -0.9997671337217909 0.02157958131462663 1.539709831518109e-032 -0.9801191546728204 -0.1984097846464127 6.67810384924031e-032 -0.9801191546728204 -0.1984097846464127 6.67810384924031e-032 -0.9126596261640011 -0.4087204506385578 1.149073085081814e-031 -0.9126596261640011 -0.4087204506385578 1.149073085081814e-031 -0.8006793160253677 -0.5990931754653439 1.574282432564735e-031 -0.8006793160253677 -0.5990931754653439 1.574282432564735e-031 -0.6496407765509797 -0.7602413178999415 1.9226961353246e-031 -0.6496407765509797 -0.7602413178999415 1.9226961353246e-031 -0.5617119664874528 -0.8273328633052111 2.062622892710896e-031 -0.5617119664874528 -0.8273328633052111 2.062622892710896e-031 -0.4669118737456301 -0.8843038517135073 2.177318097629222e-031 -0.4669118737456301 -0.8843038517135073 2.177318097629222e-031 -0.4669118737456301 -0.8843038517135073 2.177318097629222e-031 -0.4669118737456301 -0.8843038517135073 2.177318097629222e-031 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.1305261922200457 -0.9914448613738112 -3.771590375694363e-017 -0.06540312923042768 -0.9978589232385848 -3.802352049403922e-017 -0.1305261922200457 -0.9914448613738112 -3.771590375694363e-017 -0.06540312923042768 -0.9978589232385848 -3.802352049403922e-017 -0.2588190451023318 -0.9659258262891188 -3.661816326487966e-017 -0.2588190451023318 -0.9659258262891188 -3.661816326487966e-017 -0.3826834323651677 -0.9238795325112544 -3.489387584687525e-017 -0.3826834323651677 -0.9238795325112544 -3.489387584687525e-017 -0.5000000000000009 -0.8660254037844382 -3.25725445387254e-017 -0.5000000000000009 -0.8660254037844382 -3.25725445387254e-017 -0.6087614290086468 -0.7933533402912919 -2.969388796270346e-017 -0.6087614290086468 -0.7933533402912919 -2.969388796270346e-017 -0.707106781186616 -0.707106781186479 -2.630716073093143e-017 -0.707106781186616 -0.707106781186479 -2.630716073093143e-017 -0.7933533402912433 -0.6087614290087099 -2.247031068533741e-017 -0.7933533402912433 -0.6087614290087099 -2.247031068533741e-017 -0.8660254037844346 -0.5000000000000071 -1.824898739396858e-017 -0.8660254037844346 -0.5000000000000071 -1.824898739396858e-017 -0.9238795325113181 -0.3826834323650143 -1.371541886870991e-017 -0.9238795325113181 -0.3826834323650143 -1.371541886870991e-017 -0.9659258262890479 -0.2588190451025965 -8.947175723984055e-018 -0.9659258262890479 -0.2588190451025965 -8.947175723984055e-018 -0.991444861373845 -0.130526192219789 -4.025843921976333e-018 -0.991444861373845 -0.130526192219789 -4.025843921976333e-018 -0.9978589232386543 -0.06540312922937021 -1.534020824458279e-018 -0.9978589232386543 -0.06540312922937021 -1.534020824458279e-018 0.1305261922200759 0.9914448613738072 -2.360634470126157e-031 0.0654031292301361 0.997858923238604 -2.362395058420794e-031 0.1305261922200759 0.9914448613738072 -2.360634470126157e-031 0.0654031292301361 0.997858923238604 -2.362395058420794e-031 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -0.06540312922959453 0.9978589232386395 -0 -0.1305261922200789 0.9914448613738068 0 -0.06540312922959453 0.9978589232386395 -0 -0.1305261922200789 0.9914448613738068 0 -2.847216503390403e-016 -1 2.354039508393783e-031 -2.847216503390403e-016 -1 2.354039508393783e-031 -2.847216503390403e-016 -1 2.354039508393783e-031 -2.847216503390403e-016 -1 2.354039508393783e-031 -2.847216503390403e-016 -1 2.354039508393783e-031 -0.1305261922203011 -0.9914448613737775 0 -0.06540312923079149 -0.9978589232385611 -0 -0.1305261922203011 -0.9914448613737775 0 -0.06540312923079149 -0.9978589232385611 -0 0.2588190451025202 0.9659258262890684 -2.326838321583154e-031 0.2588190451025202 0.9659258262890684 -2.326838321583154e-031 -0.2588190451024253 -0.9659258262890939 0 -0.2588190451024253 -0.9659258262890939 0 -0.3826834323650169 -0.9238795325113171 0 -0.3826834323650169 -0.9238795325113171 0 -0.4999999999999031 -0.8660254037844946 0 -0.4999999999999031 -0.8660254037844946 0 -0.6087614290086439 -0.7933533402912941 0 -0.6087614290086439 -0.7933533402912941 0 -0.7071067811866093 -0.7071067811864858 0 -0.7071067811866093 -0.7071067811864858 0 -0.7933533402914218 -0.6087614290084773 0 -0.7933533402914218 -0.6087614290084773 0 -0.8660254037845377 -0.4999999999998284 0 -0.8660254037845377 -0.4999999999998284 0 -0.9238795325112122 -0.3826834323652698 0 -0.9238795325112122 -0.3826834323652698 0 -0.9659258262890901 -0.2588190451024401 0 -0.9659258262890901 -0.2588190451024401 0 -0.9914448613738833 -0.1305261922194982 0 -0.9914448613738833 -0.1305261922194982 0 -0.997858923238638 -0.06540312922961909 -0 -0.997858923238638 -0.06540312922961909 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -0.9978589232386694 0.06540312922913877 -0 -0.9914448613739054 0.1305261922193298 0 -0.9914448613739054 0.1305261922193298 0 -0.9978589232386694 0.06540312922913877 -0 -0.9659258262890584 0.2588190451025578 0 -0.9659258262890584 0.2588190451025578 0 -0.923879532511276 0.3826834323651157 0 -0.923879532511276 0.3826834323651157 0 -0.8660254037843593 0.5000000000001372 0 -0.8660254037843593 0.5000000000001372 0 -0.793353340290994 0.608761429009035 0 -0.793353340290994 0.608761429009035 0 -0.7071067811861586 0.7071067811869366 0 -0.7071067811861586 0.7071067811869366 0 -0.6087614290088786 0.793353340291114 0 -0.6087614290088786 0.793353340291114 0 -0.5000000000005405 0.8660254037841265 0 -0.5000000000005405 0.8660254037841265 0 -0.3826834323649039 0.9238795325113639 0 -0.3826834323649039 0.9238795325113639 0 -0.2588190451027368 0.9659258262890103 0 -0.2588190451027368 0.9659258262890103 0 0.0654031292301436 -0.9978589232386035 2.33560359979311e-031 0.1305261922200579 -0.9914448613738096 2.307166278009732e-031 0.0654031292301436 -0.9978589232386035 2.33560359979311e-031 0.1305261922200579 -0.9914448613738096 2.307166278009732e-031 0.382683432365069 0.9238795325112953 -2.253229324236416e-031 0.382683432365069 0.9238795325112953 -2.253229324236416e-031 0.2588190451025239 -0.9659258262890675 2.220816792941599e-031 0.2588190451025239 -0.9659258262890675 2.220816792941599e-031 0.5000000000000147 0.8660254037844301 -2.141066948438753e-031 0.5000000000000147 0.8660254037844301 -2.141066948438753e-031 0.3826834323650852 -0.9238795325112886 2.096468516819501e-031 0.3826834323650852 -0.9238795325112886 2.096468516819501e-031 0.6087614290087049 0.7933533402912473 -1.992270323537472e-031 0.6087614290087049 0.7933533402912473 -1.992270323537472e-031 0.4999999999999988 -0.8660254037844394 1.936249083123728e-031 0.4999999999999988 -0.8660254037844394 1.936249083123728e-031 0.7071067811865293 0.7071067811865658 -1.809385401038751e-031 0.7071067811865293 0.7071067811865658 -1.809385401038751e-031 0.6087614290087232 -0.7933533402912332 1.742899890786038e-031 0.6087614290087232 -0.7933533402912332 1.742899890786038e-031 0.7933533402912396 0.6087614290087149 -1.595541392671784e-031 0.7933533402912396 0.6087614290087149 -1.595541392671784e-031 0.7071067811865497 -0.7071067811865455 1.519729198093864e-031 0.7071067811865497 -0.7071067811865455 1.519729198093864e-031 0.8660254037844386 0.4999999999999999 -1.35439722870862e-031 0.8660254037844386 0.4999999999999999 -1.35439722870862e-031 0.7933533402912354 -0.6087614290087204 1.270555517473774e-031 0.7933533402912354 -0.6087614290087204 1.270555517473774e-031 0.9238795325112905 0.3826834323650806 -1.090078952652364e-031 0.9238795325112905 0.3826834323650806 -1.090078952652364e-031 0.8660254037844404 -0.4999999999999971 9.996422796851562e-032 0.8660254037844404 -0.4999999999999971 9.996422796851562e-032 0.9659258262890674 0.258819045102524 -8.071091234892916e-032 0.9659258262890674 0.258819045102524 -8.071091234892916e-032 0.9238795325112879 -0.3826834323650874 7.116248853379323e-032 0.9238795325112879 -0.3826834323650874 7.116248853379323e-032 0.9914448613738091 0.1305261922200617 -5.103294334503805e-032 0.9914448613738091 0.1305261922200617 -5.103294334503805e-032 0.965925826289068 -0.2588190451025222 4.114313919028921e-032 0.965925826289068 -0.2588190451025222 4.114313919028921e-032 0.9978589232386044 0.06540312923013249 -3.583408847236163e-032 0.9978589232386044 0.06540312923013249 -3.583408847236163e-032 0.9914448613738105 -0.1305261922200517 1.041981932820484e-032 0.9914448613738105 -0.1305261922200517 1.041981932820484e-032 1 -3.846068690370998e-016 -2.04817865315044e-032 1 -3.846068690370998e-016 -2.04817865315044e-032 1 -3.846068690370998e-016 -2.04817865315044e-032 1 -3.846068690370998e-016 -2.04817865315044e-032 0.9978589232386037 -0.0654031292301418 -5.041778436296195e-033 0.9978589232386037 -0.0654031292301418 -5.041778436296195e-033 + + + + + + + + + + + + + + +

0 1 2 1 0 3 4 5 6 5 4 2 2 4 0 3 7 1 7 3 8 9 10 11 10 9 12 12 9 13 13 9 14 14 9 15 15 9 16 16 9 17 17 9 18 18 9 19 18 19 20 18 20 21 21 20 22 21 22 23 23 22 24 24 22 25 24 25 26 26 25 27 26 27 28 26 28 29 29 28 30 30 28 31 30 31 32 30 32 33 33 32 34 33 34 35 35 34 36 36 34 37 36 37 38 38 37 39 38 39 40 40 39 41 42 17 43 17 42 44 17 44 45 17 45 46 17 46 47 17 47 16 48 49 50 49 48 51 52 53 54 53 52 55 53 55 56 57 54 53 8 58 7 58 8 59 60 61 62 61 60 63 64 65 66 65 64 67 66 68 69 68 66 65 69 70 71 70 69 68 71 72 73 72 71 70 73 74 75 74 73 72 75 76 77 76 75 74 78 76 79 76 78 77 80 79 81 79 80 78 82 81 83 81 82 80 84 83 85 83 84 82 86 85 87 85 86 84 88 87 89 87 88 86 90 58 59 58 90 91 92 91 90 91 92 93 94 93 92 93 94 95 96 95 94 95 96 97 98 97 96 97 98 99 100 99 98 99 100 101 102 101 100 101 102 103 102 104 103 104 102 105 106 107 108 107 106 109 110 111 112 111 110 113 111 113 114 114 113 115 116 117 118 117 116 119 120 118 121 118 120 116 122 121 123 121 122 120 124 123 125 123 124 122 126 125 127 125 126 124 128 127 129 127 128 126 128 130 131 130 128 129 131 132 133 132 131 130 133 134 135 134 133 132 135 136 137 136 135 134 137 138 139 138 137 136 139 140 141 140 139 138 142 143 144 143 142 145 146 147 148 147 146 149 149 146 150 150 146 151 151 146 152 152 146 153 153 146 154 154 146 155 155 146 156 156 146 157 157 146 158 158 146 159 159 146 160 161 162 163 162 161 164 162 164 165 162 165 166 162 166 167 162 167 168 162 168 169 162 169 170 162 170 171 162 171 172 162 172 173 162 173 160 162 160 146 162 146 174 162 174 175 175 174 176 176 174 177 176 177 178 178 177 179 178 179 180 180 179 181 180 181 182 180 182 183 183 182 184 184 182 185 184 185 186 186 185 187 186 187 188 188 187 189 188 189 190 188 190 191 191 190 192 191 192 193 193 192 194 193 194 195 195 194 196 195 196 197 198 199 200 199 198 201 202 203 204 203 202 205 205 202 206 207 208 209 208 207 210 211 144 212 144 211 142 213 209 214 209 213 207 215 214 216 214 215 213 217 216 218 216 217 215 219 218 220 218 219 217 221 220 222 220 221 219 221 223 224 223 221 222 224 225 226 225 224 223 226 227 228 227 226 225 228 229 230 229 228 227 230 231 232 231 230 229 232 233 234 233 232 231 235 236 237 236 235 238 239 240 241 240 239 242 241 243 244 243 241 240 244 245 246 245 244 243 246 247 248 247 246 245 248 249 250 249 248 247 250 251 252 251 250 249 253 251 254 251 253 252 255 254 256 254 255 253 257 256 258 256 257 255 259 258 260 258 259 257 201 260 199 260 201 259 261 262 263 262 261 264 265 212 266 212 265 211 264 267 262 267 264 268 269 266 270 266 269 265 268 271 267 271 268 272 273 270 274 270 273 269 272 275 271 275 272 276 277 274 278 274 277 273 276 279 275 279 276 280 281 277 278 277 281 282 280 283 279 283 280 284 285 282 281 282 285 286 283 287 288 287 283 284 289 286 285 286 289 290 288 291 292 291 288 287 293 290 289 290 293 294 292 295 296 295 292 291 297 294 293 294 297 298 296 299 300 299 296 295 301 298 297 298 301 302 300 303 304 303 300 299 305 306 307 306 305 308 304 309 310 309 304 303

+
+
+
+ + + + 43.38400397036494 7.421059675912715 0.07874015748031579 43.37882183390003 3.127233759244795 0.07874015748031607 43.37882183390003 7.395007316609055 0.07874015748031579 43.38055912121086 3.10072787694619 0.07874015748031607 43.38574125767577 3.074675517642528 0.07874015748031607 43.39254228819227 7.446212749130662 0.07874015748031579 43.39427957550313 3.04952244442458 0.07874015748031607 43.40429069439674 7.470036160206389 0.07874015748031579 43.4060279817076 3.025699033348864 0.07874015748031607 43.4132129304469 7.39162008924713 0.07874015748031579 43.41904817049088 7.492122283971291 0.07874015748031579 43.41729449628541 7.412139506376729 0.07874015748031579 43.42438369328506 7.43302360729623 0.07874015748031579 43.43656221196721 7.512093220724323 0.07874015748031579 43.4341381633926 7.452803715947015 0.07874015748031579 43.44639100492 7.47114138918596 0.07874015748031579 43.45653314872024 7.529607262200647 0.07874015748031579 43.46093256835167 7.487722864339863 0.07874015748031579 43.47861927248514 7.544364738294798 0.07874015748031579 43.47751404350557 7.502264427771523 0.07874015748031579 43.49585171674453 7.514517269298941 0.07874015748031579 43.50244268356087 7.556113144499255 0.07874015748031579 43.51563182539531 7.524271739406478 0.07874015748031579 43.52759575677882 7.56465146232659 0.07874015748031579 43.53651592631481 7.531360936406135 0.07874015748031579 43.55364811608248 7.569833598791506 0.07874015748031579 43.55703534344437 7.535442502244626 0.07874015748031579 50.144256319116 7.569833598791506 0.07874015748031607 50.14313047118674 7.535442502244621 0.07874015748031607 50.16626363075097 7.53392627486092 0.07874015748031607 50.1707622014146 7.568096311480678 0.07874015748031607 50.18789439118228 7.529623649095314 0.07874015748031607 50.19681456071828 7.562914175015767 0.07874015748031607 50.20877849210176 7.522534452095655 0.07874015748031607 50.22196763393622 7.554375857188427 0.07874015748031607 50.22855860075256 7.512779981988107 0.07874015748031607 50.24579104501194 7.542627450983966 0.07874015748031607 50.24689627399151 7.500527140460703 0.07874015748031607 50.26787716877683 7.527869974889834 0.07874015748031607 50.26347774914542 7.485985577029031 0.07874015748031607 50.27801931257708 7.469404101875151 0.07874015748031607 50.28784810552988 7.510355933413502 0.07874015748031607 50.29027215410449 7.451066428636207 0.07874015748031607 50.3053621470062 7.490384996660477 0.07874015748031607 50.30002662421204 7.431286319985366 0.07874015748031607 50.30711582121172 7.410402219065904 0.07874015748031607 50.32011962310036 7.468298872895575 0.07874015748031607 50.31141844697731 7.388771458634578 0.07874015748031607 50.31293467436102 7.365638299070358 0.07874015748031607 50.31293467436102 3.128359607174147 0.07874015748031607 50.32011962310035 3.025699033348873 0.07874015748031607 50.33186802930481 3.049522444424608 0.07874015748031607 50.3318680293048 7.44447546181984 0.07874015748031607 50.34040634713218 7.419322388601879 0.07874015748031607 50.34040634713214 3.074675517642548 0.07874015748031607 50.34558848359704 3.100727876946217 0.07874015748031607 50.34558848359706 7.393270029298235 0.07874015748031607 50.3473257709079 3.127233759244805 0.07874015748031607 50.3473257709079 7.366764146999632 0.07874015748031607 43.4132129304469 3.128359607174164 0.07874015748031607 43.42078545780171 3.003612909583954 0.07874015748031607 43.41472915783061 3.105226447609857 0.07874015748031607 43.41903178359623 3.083595687178518 0.07874015748031607 43.4261209805959 3.062711586259032 0.07874015748031607 43.43829949927805 2.98364197283092 0.07874015748031607 43.43587545070344 3.042931477608274 0.07874015748031607 43.44812829223088 3.024593804369232 0.07874015748031607 43.45827043603106 2.96612793135459 0.07874015748031607 43.46266985566252 3.008012329215369 0.07874015748031607 43.480356559796 2.951370455260453 0.07874015748031607 43.47925133081637 2.993470765783733 0.07874015748031607 43.49758900405537 2.981217924256313 0.07874015748031607 43.5041799708717 2.939622049055988 0.07874015748031607 43.51736911270614 2.971463454148768 0.07874015748031607 43.52933304408965 2.931083731228659 0.07874015748031607 43.53825321362565 2.964374257149114 0.07874015748031607 43.55538540339332 2.925901594763743 0.07874015748031607 43.55988397405696 2.960071631383501 0.07874015748031607 43.58189128569192 2.924164307452924 0.07874015748031607 43.58301713362136 2.958555403999797 0.07874015748031607 50.14425631911599 2.924164307452924 0.07874015748031607 50.14313047118665 2.958555403999804 0.07874015748031607 50.166263630751 2.960071631383512 0.07874015748031607 50.17076220141464 2.925901594763754 0.07874015748031607 50.1878943911823 2.96437425714911 0.07874015748031607 50.19681456071832 2.931083731228657 0.07874015748031607 50.20877849210176 2.971463454148789 0.07874015748031607 50.22196763393622 2.939622049056019 0.07874015748031607 50.22855860075259 2.981217924256331 0.07874015748031607 50.24579104501196 2.951370455260466 0.07874015748031607 50.24689627399157 2.993470765783735 0.07874015748031607 50.26787716877688 2.966127931354595 0.07874015748031607 50.26347774914544 3.008012329215407 0.07874015748031607 50.27801931257705 3.024593804369262 0.07874015748031607 50.28784810552991 2.98364197283095 0.07874015748031607 50.2902721541045 3.042931477608267 0.07874015748031607 50.3053621470062 3.003612909583975 0.07874015748031607 50.30002662421204 3.062711586259064 0.07874015748031607 50.30711582121167 3.083595687178512 0.07874015748031607 50.31141844697729 3.105226447609863 0.07874015748031607 50.144256319116 7.569833598791506 1.090510587941475e-015 43.55364811608248 7.569833598791506 0.07874015748031579 43.55364811608248 7.569833598791506 8.326672684688674e-016 50.144256319116 7.569833598791506 0.07874015748031607 50.1707622014146 7.568096311480678 0.07874015748031607 50.144256319116 7.569833598791506 1.090510587941475e-015 50.1707622014146 7.568096311480678 1.090510587941475e-015 50.144256319116 7.569833598791506 0.07874015748031607 50.19681456071828 7.562914175015767 0.07874015748031607 50.19681456071828 7.562914175015767 1.090510587941475e-015 50.22196763393622 7.554375857188427 0.07874015748031607 50.22196763393622 7.554375857188427 1.090510587941475e-015 50.24579104501194 7.542627450983966 0.07874015748031607 50.24579104501194 7.542627450983966 1.090510587941475e-015 50.26787716877683 7.527869974889834 0.07874015748031607 50.26787716877683 7.527869974889834 1.090510587941475e-015 50.28784810552988 7.510355933413502 0.07874015748031607 50.28784810552988 7.510355933413502 1.090510587941475e-015 50.3053621470062 7.490384996660477 1.090510587941475e-015 50.3053621470062 7.490384996660477 0.07874015748031607 50.32011962310036 7.468298872895575 1.118266163557104e-015 50.32011962310036 7.468298872895575 0.07874015748031607 50.3318680293048 7.44447546181984 1.118266163557104e-015 50.3318680293048 7.44447546181984 0.07874015748031607 50.34040634713218 7.419322388601879 1.118266163557104e-015 50.34040634713218 7.419322388601879 0.07874015748031607 50.34558848359706 7.393270029298235 1.118266163557104e-015 50.34558848359706 7.393270029298235 0.07874015748031607 50.3473257709079 7.366764146999632 1.118266163557104e-015 50.3473257709079 7.366764146999632 0.07874015748031607 50.3473257709079 7.366764146999632 0.07874015748031607 50.3473257709079 3.127233759244805 1.103017739216966e-015 50.3473257709079 3.127233759244805 0.07874015748031607 50.3473257709079 7.366764146999632 1.118266163557104e-015 50.3473257709079 3.127233759244805 0.07874015748031607 50.34558848359704 3.100727876946217 1.105899590885709e-015 50.34558848359704 3.100727876946217 0.07874015748031607 50.3473257709079 3.127233759244805 1.103017739216966e-015 50.34040634713214 3.074675517642548 1.108591182719098e-015 50.34040634713214 3.074675517642548 0.07874015748031607 50.33186802930481 3.049522444424608 1.111046460834616e-015 50.33186802930481 3.049522444424608 0.07874015748031607 50.32011962310035 3.025699033348873 1.113223414742969e-015 50.32011962310035 3.025699033348873 0.07874015748031607 50.3053621470062 3.003612909583975 1.115084796159225e-015 50.3053621470062 3.003612909583975 0.07874015748031607 50.28784810552991 2.98364197283095 1.116598756331273e-015 50.28784810552991 2.98364197283095 0.07874015748031607 50.26787716877688 2.966127931354595 1.11773939098083e-015 50.26787716877688 2.966127931354595 0.07874015748031607 50.24579104501196 2.951370455260466 1.11848718353279e-015 50.24579104501196 2.951370455260466 0.07874015748031607 50.22196763393622 2.939622049056019 1.118829339049262e-015 50.22196763393622 2.939622049056019 0.07874015748031607 50.19681456071832 2.931083731228657 0.07874015748031607 50.19681456071832 2.931083731228657 1.118760003154504e-015 50.17076220141464 2.925901594763754 0.07874015748031607 50.17076220141464 2.925901594763754 1.118280362204888e-015 50.14425631911599 2.924164307452924 0.07874015748031607 50.14425631911599 2.924164307452924 1.117398622990049e-015 43.58189128569192 2.924164307452924 0.07874015748031607 50.14425631911599 2.924164307452924 1.117398622990049e-015 43.58189128569192 2.924164307452924 1.109233975091996e-015 50.14425631911599 2.924164307452924 0.07874015748031607 43.55538540339332 2.925901594763743 1.109463768595622e-015 43.58189128569192 2.924164307452924 0.07874015748031607 43.58189128569192 2.924164307452924 1.109233975091996e-015 43.55538540339332 2.925901594763743 0.07874015748031607 43.52933304408965 2.931083731228659 0.07874015748031607 43.52933304408965 2.931083731228659 1.109462778393509e-015 43.5041799708717 2.939622049055988 0.07874015748031607 43.5041799708717 2.939622049055988 1.109231021428294e-015 43.480356559796 2.951370455260453 0.07874015748031607 43.480356559796 2.951370455260453 1.108772463125903e-015 43.45827043603106 2.96612793135459 0.07874015748031607 43.45827043603106 2.96612793135459 1.108094949546031e-015 43.43829949927805 2.98364197283092 0.07874015748031607 43.43829949927805 2.98364197283092 1.107210073133866e-015 43.42078545780171 3.003612909583954 1.106132974370159e-015 43.42078545780171 3.003612909583954 0.07874015748031607 43.4060279817076 3.025699033348864 1.104882082713383e-015 43.4060279817076 3.025699033348864 0.07874015748031607 43.39427957550313 3.04952244442458 1.1034788012666e-015 43.39427957550313 3.04952244442458 0.07874015748031607 43.38574125767577 3.074675517642528 1.101947140564425e-015 43.38574125767577 3.074675517642528 0.07874015748031607 43.38055912121086 3.10072787694619 1.100313307746131e-015 43.38055912121086 3.10072787694619 0.07874015748031607 43.37882183390003 3.127233759244795 1.098605258144222e-015 43.37882183390003 3.127233759244795 0.07874015748031607 43.37882183390003 7.395007316609055 8.326672684688674e-016 43.37882183390003 3.127233759244795 0.07874015748031607 43.37882183390003 3.127233759244795 1.098605258144222e-015 43.37882183390003 7.395007316609055 0.07874015748031579 43.38400397036494 7.421059675912715 8.326672684688674e-016 43.37882183390003 7.395007316609055 0.07874015748031579 43.37882183390003 7.395007316609055 8.326672684688674e-016 43.38400397036494 7.421059675912715 0.07874015748031579 43.39254228819227 7.446212749130662 8.326672684688674e-016 43.39254228819227 7.446212749130662 0.07874015748031579 43.40429069439674 7.470036160206389 8.326672684688674e-016 43.40429069439674 7.470036160206389 0.07874015748031579 43.41904817049088 7.492122283971291 8.326672684688674e-016 43.41904817049088 7.492122283971291 0.07874015748031579 43.43656221196721 7.512093220724323 8.326672684688674e-016 43.43656221196721 7.512093220724323 0.07874015748031579 43.45653314872024 7.529607262200647 0.07874015748031579 43.45653314872024 7.529607262200647 8.326672684688674e-016 43.47861927248514 7.544364738294798 0.07874015748031579 43.47861927248514 7.544364738294798 8.326672684688674e-016 43.50244268356087 7.556113144499255 0.07874015748031579 43.50244268356087 7.556113144499255 8.326672684688674e-016 43.52759575677882 7.56465146232659 0.07874015748031579 43.52759575677882 7.56465146232659 8.326672684688674e-016 43.55364811608248 7.569833598791506 0.07874015748031579 43.55364811608248 7.569833598791506 8.326672684688674e-016 + + + + + + + + + + 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.1305261922199813 -0.9914448613738196 2.780848713701879e-017 -0.06540312923029371 -0.9978589232385937 2.927210314289912e-017 -0.1305261922199813 -0.9914448613738196 2.780848713701879e-017 -0.06540312923029371 -0.9978589232385937 2.927210314289912e-017 -0.2588190451024848 -0.965925826289078 2.453079183995709e-017 -0.2588190451024848 -0.965925826289078 2.453079183995709e-017 -0.382683432365306 -0.9238795325111974 2.083336789328604e-017 -0.382683432365306 -0.9238795325111974 2.083336789328604e-017 -0.5000000000000238 -0.8660254037844249 1.677947924587394e-017 -0.5000000000000238 -0.8660254037844249 1.677947924587394e-017 -0.6087614290084881 -0.7933533402914136 1.24384890564192e-017 -0.6087614290084881 -0.7933533402914136 1.24384890564192e-017 -0.7071067811864248 -0.7071067811866704 7.884672870593892e-018 -0.7071067811864248 -0.7071067811866704 7.884672870593892e-018 -0.7933533402911389 -0.6087614290088461 3.195947745911922e-018 -0.7933533402911389 -0.6087614290088461 3.195947745911922e-018 -0.8660254037845401 -0.4999999999998245 -1.547460930799239e-018 -0.8660254037845401 -0.4999999999998245 -1.54746093079924e-018 -0.923879532511154 -0.3826834323654104 -6.264392121914531e-018 -0.923879532511154 -0.3826834323654104 -6.264392121914531e-018 -0.9659258262890302 -0.2588190451026624 -1.087413782703309e-017 -0.9659258262890302 -0.2588190451026624 -1.087413782703309e-017 -0.9914448613738499 -0.1305261922197522 -1.529782401905813e-017 -0.9914448613738499 -0.1305261922197522 -1.529782401905813e-017 -0.9978589232385668 -0.06540312923070414 -1.741608127676964e-017 -0.9978589232385668 -0.06540312923070414 -1.741608127676964e-017 -1 6.99914032825858e-035 -1.945976020073421e-017 -1 6.99914032825858e-035 -1.945976020073421e-017 -1 6.99914032825858e-035 -1.945976020073421e-017 -1 6.99914032825858e-035 -1.945976020073421e-017 -0.997858923238512 0.06540312923154029 -2.142010944402561e-017 -0.9914448613737562 0.1305261922204639 -2.328873449013242e-017 -0.9914448613737562 0.1305261922204639 -2.328873449013242e-017 -0.997858923238512 0.06540312923154029 -2.142010944402561e-017 -0.9659258262891491 0.2588190451022194 -2.671923207551683e-017 -0.9659258262891491 0.2588190451022194 -2.671923207551682e-017 -0.9238795325113062 0.3826834323650429 -2.969255619214416e-017 -0.9238795325113063 0.3826834323650429 -2.969255619214416e-017 -0.8660254037844481 0.4999999999999837 -3.215783243998618e-017 -0.8660254037844481 0.4999999999999837 -3.215783243998619e-017 -0.7933533402914976 0.6087614290083786 -3.40728792589387e-017 -0.7933533402914977 0.6087614290083787 -3.407287925893871e-017 -0.7071067811871351 0.7071067811859598 -3.540492966698771e-017 -0.707106781187135 0.70710678118596 -3.54049296669877e-017 -0.6087614290086183 0.7933533402913137 -3.61311919123416e-017 -0.6087614290086183 0.7933533402913137 -3.61311919123416e-017 -0.4999999999992923 0.8660254037848472 -3.623923944660778e-017 -0.4999999999992923 0.8660254037848472 -3.623923944660778e-017 -0.3826834323655242 0.9238795325111068 -3.5727223546533e-017 -0.3826834323655242 0.9238795325111068 -3.5727223546533e-017 -0.2588190451029578 0.9659258262889511 -3.460390494611714e-017 -0.2588190451029578 0.9659258262889511 -3.460390494611714e-017 -0.1305261922198164 0.9914448613738415 -3.28885039380478e-017 -0.1305261922198164 0.9914448613738415 -3.28885039380478e-017 -0.06540312923028883 0.997858923238594 -3.181756156529731e-017 -0.06540312923028883 0.997858923238594 -3.181756156529731e-017 6.767212850674795e-017 1 -3.061037150919461e-017 6.767212850674795e-017 1 -3.061037150919461e-017 6.767212850674795e-017 1 -3.061037150919461e-017 6.767212850674795e-017 1 -3.061037150919461e-017 0.1305261922199325 0.991444861373826 -2.780848713701993e-017 0.06540312922994411 0.9978589232386167 -2.927210314290662e-017 0.06540312922994411 0.9978589232386167 -2.927210314290662e-017 0.1305261922199325 0.991444861373826 -2.780848713701993e-017 0.2588190451023891 0.9659258262891036 -2.453079183995972e-017 0.2588190451023891 0.9659258262891036 -2.453079183995972e-017 0.3826834323652765 0.9238795325112095 -2.083336789328698e-017 0.3826834323652765 0.9238795325112095 -2.083336789328698e-017 0.4999999999998008 0.8660254037845535 -1.677947924588222e-017 0.4999999999998008 0.8660254037845535 -1.677947924588222e-017 0.6087614290084553 0.7933533402914387 -1.24384890564206e-017 0.6087614290084553 0.7933533402914387 -1.24384890564206e-017 0.7071067811866578 0.7071067811864372 -7.884672870582221e-018 0.7071067811866578 0.7071067811864372 -7.884672870582221e-018 0.7933533402916122 0.6087614290082292 -3.195947745883828e-018 0.7933533402916122 0.6087614290082292 -3.195947745883828e-018 0.8660254037845893 0.499999999999739 1.547460930802815e-018 0.8660254037845894 0.4999999999997391 1.547460930802815e-018 0.9238795325109803 0.3826834323658298 6.26439212189831e-018 0.9238795325109803 0.3826834323658298 6.26439212189831e-018 0.9659258262889898 0.2588190451028135 1.087413782702768e-017 0.9659258262889898 0.2588190451028135 1.087413782702768e-017 0.9914448613738075 0.1305261922200738 1.529782401904747e-017 0.9914448613738075 0.1305261922200738 1.529782401904747e-017 0.9978589232385846 0.06540312923043123 1.741608127677834e-017 0.9978589232385846 0.06540312923043123 1.741608127677834e-017 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 0.9659258262890843 -0.2588190451024608 1.416353255915568e-017 0.9807852804032251 -0.1950903220161558 -0 0.9807852804032251 -0.1950903220161558 -0 0.9659258262890843 -0.2588190451024608 1.416353255915568e-017 0.9238795325112965 -0.3826834323650666 2.96925561921447e-017 0.9238795325112965 -0.3826834323650666 2.96925561921447e-017 0.8660254037844343 -0.5000000000000074 3.215783243998664e-017 0.8660254037844343 -0.5000000000000074 3.215783243998664e-017 0.7933533402912668 -0.6087614290086795 3.407287925894342e-017 0.7933533402912668 -0.6087614290086795 3.407287925894342e-017 0.7071067811865319 -0.707106781186563 3.540492966699442e-017 0.7071067811865319 -0.707106781186563 3.540492966699442e-017 0.6087614290087207 -0.7933533402912351 3.613119191234118e-017 0.6087614290087207 -0.7933533402912351 3.613119191234118e-017 0.4999999999999814 -0.8660254037844495 3.623923944660901e-017 0.4999999999999814 -0.8660254037844495 3.623923944660901e-017 0.382683432365068 -0.9238795325112956 3.572722354652991e-017 0.382683432365068 -0.9238795325112956 3.572722354652991e-017 0.2588190451025379 -0.9659258262890638 1.765831679721354e-017 0.2588190451025379 -0.9659258262890638 1.765831679721354e-017 0.1950903220161044 -0.9807852804032353 0 0.1950903220161044 -0.9807852804032353 0 + + + + + + + + + + + + + + +

0 1 2 1 0 3 3 0 4 4 0 5 4 5 6 6 5 7 6 7 8 8 7 9 9 7 10 9 10 11 11 10 12 12 10 13 12 13 14 14 13 15 15 13 16 15 16 17 17 16 18 17 18 19 19 18 20 20 18 21 20 21 22 22 21 23 22 23 24 24 23 25 24 25 26 26 25 27 26 27 28 28 27 29 29 27 30 29 30 31 31 30 32 31 32 33 33 32 34 33 34 35 35 34 36 35 36 37 37 36 38 37 38 39 39 38 40 40 38 41 40 41 42 42 41 43 42 43 44 44 43 45 45 43 46 45 46 47 47 46 48 48 46 49 49 46 50 50 46 51 51 46 52 51 52 53 51 53 54 54 53 55 55 53 56 55 56 57 57 56 58 8 59 60 59 8 9 60 59 61 60 61 62 60 62 63 60 63 64 64 63 65 64 65 66 64 66 67 67 66 68 67 68 69 69 68 70 69 70 71 69 71 72 72 71 73 72 73 74 74 73 75 74 75 76 76 75 77 76 77 78 78 77 79 78 79 80 80 79 81 80 81 82 80 82 83 83 82 84 83 84 85 85 84 86 85 86 87 87 86 88 87 88 89 89 88 90 89 90 91 91 90 92 91 92 93 91 93 94 94 93 95 94 95 96 96 95 97 96 97 98 96 98 50 50 98 99 50 99 49 100 101 102 101 100 103 104 105 106 105 104 107 108 106 109 106 108 104 110 109 111 109 110 108 112 111 113 111 112 110 114 113 115 113 114 112 116 115 117 115 116 114 116 118 119 118 116 117 119 120 121 120 119 118 121 122 123 122 121 120 123 124 125 124 123 122 125 126 127 126 125 124 127 128 129 128 127 126 130 131 132 131 130 133 134 135 136 135 134 137 136 138 139 138 136 135 139 140 141 140 139 138 141 142 143 142 141 140 143 144 145 144 143 142 145 146 147 146 145 144 148 147 146 147 148 149 150 149 148 149 150 151 152 151 150 151 152 153 154 152 155 152 154 153 156 155 157 155 156 154 158 157 159 157 158 156 160 161 162 161 160 163 164 165 166 165 164 167 168 164 169 164 168 167 170 169 171 169 170 168 172 171 173 171 172 170 174 173 175 173 174 172 176 175 177 175 176 174 178 176 177 176 178 179 180 179 178 179 180 181 182 181 180 181 182 183 184 183 182 183 184 185 186 185 184 185 186 187 188 187 186 187 188 189 190 191 192 191 190 193 194 195 196 195 194 197 198 197 194 197 198 199 200 199 198 199 200 201 202 201 200 201 202 203 204 203 202 203 204 205 206 204 207 204 206 205 208 207 209 207 208 206 210 209 211 209 210 208 212 211 213 211 212 210 214 213 215 213 214 212

+
+
+
+ + + + 43.41729449628541 7.412139506376729 -0.1968503937007866 43.4132129304469 3.128359607174164 -0.1968503937007863 43.4132129304469 7.39162008924713 -0.1968503937007866 43.41472915783061 3.105226447609857 -0.1968503937007863 43.41903178359623 3.083595687178518 -0.1968503937007863 43.42438369328506 7.43302360729623 -0.1968503937007866 43.4261209805959 3.062711586259032 -0.1968503937007863 43.4341381633926 7.452803715947015 -0.1968503937007866 43.43587545070344 3.042931477608274 -0.1968503937007863 43.44639100492 7.47114138918596 -0.1968503937007866 43.44812829223088 3.024593804369232 -0.1968503937007863 43.46093256835167 7.487722864339863 -0.1968503937007866 43.46266985566252 3.008012329215369 -0.1968503937007863 43.47751404350557 7.502264427771523 -0.1968503937007866 43.47925133081637 2.993470765783733 -0.1968503937007863 43.49585171674453 7.514517269298941 -0.1968503937007866 43.49758900405537 2.981217924256313 -0.1968503937007863 43.51563182539531 7.524271739406478 -0.1968503937007866 43.51736911270614 2.971463454148768 -0.1968503937007863 43.53651592631481 7.531360936406135 -0.1968503937007866 43.53825321362565 2.964374257149114 -0.1968503937007863 43.55703534344437 7.535442502244626 -0.1968503937007866 43.55988397405696 2.960071631383501 -0.1968503937007863 50.14313047118674 7.535442502244621 -0.1968503937007863 43.58301713362136 2.958555403999797 -0.1968503937007863 50.14313047118665 2.958555403999804 -0.1968503937007863 50.166263630751 2.960071631383512 -0.1968503937007863 50.16626363075097 7.53392627486092 -0.1968503937007863 50.18789439118228 7.529623649095314 -0.1968503937007863 50.1878943911823 2.96437425714911 -0.1968503937007863 50.20877849210176 7.522534452095655 -0.1968503937007863 50.20877849210176 2.971463454148789 -0.1968503937007863 50.22855860075256 7.512779981988107 -0.1968503937007863 50.22855860075259 2.981217924256331 -0.1968503937007863 50.24689627399151 7.500527140460703 -0.1968503937007863 50.24689627399157 2.993470765783735 -0.1968503937007863 50.26347774914542 7.485985577029031 -0.1968503937007863 50.26347774914544 3.008012329215407 -0.1968503937007863 50.27801931257708 7.469404101875151 -0.1968503937007863 50.27801931257705 3.024593804369262 -0.1968503937007863 50.2902721541045 3.042931477608267 -0.1968503937007863 50.29027215410449 7.451066428636207 -0.1968503937007863 50.30002662421204 7.431286319985366 -0.1968503937007863 50.30002662421204 3.062711586259064 -0.1968503937007863 50.30711582121172 7.410402219065904 -0.1968503937007863 50.30711582121167 3.083595687178512 -0.1968503937007863 50.31141844697729 3.105226447609863 -0.1968503937007863 50.31141844697731 7.388771458634578 -0.1968503937007863 50.31293467436102 3.128359607174147 -0.1968503937007863 50.31293467436102 7.365638299070358 -0.1968503937007863 + + + + + + + + + + 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 + + + + + + + + + + + + + + +

0 1 2 1 0 3 3 0 4 4 0 5 4 5 6 6 5 7 6 7 8 8 7 9 8 9 10 10 9 11 10 11 12 12 11 13 12 13 14 14 13 15 14 15 16 16 15 17 16 17 18 18 17 19 18 19 20 20 19 21 20 21 22 22 21 23 22 23 24 24 23 25 25 23 26 26 23 27 26 27 28 26 28 29 29 28 30 29 30 31 31 30 32 31 32 33 33 32 34 33 34 35 35 34 36 35 36 37 37 36 38 37 38 39 39 38 40 40 38 41 40 41 42 40 42 43 43 42 44 43 44 45 45 44 46 46 44 47 46 47 48 48 47 49

+
+
+
+ + + + 50.31141844697731 7.388771458634578 -0.1968503937007863 50.31293467436102 7.365638299070358 0.07874015748031607 50.31293467436102 7.365638299070358 -0.1968503937007863 50.31141844697731 7.388771458634578 0.07874015748031607 50.31293467436102 7.365638299070358 -0.1968503937007863 50.31293467436102 3.128359607174147 0.07874015748031607 50.31293467436102 3.128359607174147 -0.1968503937007863 50.31293467436102 7.365638299070358 0.07874015748031607 50.30711582121172 7.410402219065904 -0.1968503937007863 50.30711582121172 7.410402219065904 0.07874015748031607 50.31293467436102 3.128359607174147 -0.1968503937007863 50.31141844697729 3.105226447609863 0.07874015748031607 50.31141844697729 3.105226447609863 -0.1968503937007863 50.31293467436102 3.128359607174147 0.07874015748031607 50.30002662421204 7.431286319985366 -0.1968503937007863 50.30002662421204 7.431286319985366 0.07874015748031607 50.30711582121167 3.083595687178512 0.07874015748031607 50.30711582121167 3.083595687178512 -0.1968503937007863 50.29027215410449 7.451066428636207 -0.1968503937007863 50.29027215410449 7.451066428636207 0.07874015748031607 50.30002662421204 3.062711586259064 0.07874015748031607 50.30002662421204 3.062711586259064 -0.1968503937007863 50.27801931257708 7.469404101875151 -0.1968503937007863 50.27801931257708 7.469404101875151 0.07874015748031607 50.2902721541045 3.042931477608267 0.07874015748031607 50.2902721541045 3.042931477608267 -0.1968503937007863 50.26347774914542 7.485985577029031 -0.1968503937007863 50.26347774914542 7.485985577029031 0.07874015748031607 50.27801931257705 3.024593804369262 0.07874015748031607 50.27801931257705 3.024593804369262 -0.1968503937007863 50.24689627399151 7.500527140460703 0.07874015748031607 50.24689627399151 7.500527140460703 -0.1968503937007863 50.26347774914544 3.008012329215407 0.07874015748031607 50.26347774914544 3.008012329215407 -0.1968503937007863 50.22855860075256 7.512779981988107 0.07874015748031607 50.22855860075256 7.512779981988107 -0.1968503937007863 50.24689627399157 2.993470765783735 -0.1968503937007863 50.24689627399157 2.993470765783735 0.07874015748031607 50.20877849210176 7.522534452095655 0.07874015748031607 50.20877849210176 7.522534452095655 -0.1968503937007863 50.22855860075259 2.981217924256331 -0.1968503937007863 50.22855860075259 2.981217924256331 0.07874015748031607 50.18789439118228 7.529623649095314 0.07874015748031607 50.18789439118228 7.529623649095314 -0.1968503937007863 50.20877849210176 2.971463454148789 -0.1968503937007863 50.20877849210176 2.971463454148789 0.07874015748031607 50.16626363075097 7.53392627486092 0.07874015748031607 50.16626363075097 7.53392627486092 -0.1968503937007863 50.1878943911823 2.96437425714911 -0.1968503937007863 50.1878943911823 2.96437425714911 0.07874015748031607 50.14313047118674 7.535442502244621 0.07874015748031607 50.14313047118674 7.535442502244621 -0.1968503937007863 50.166263630751 2.960071631383512 -0.1968503937007863 50.166263630751 2.960071631383512 0.07874015748031607 43.55703534344437 7.535442502244626 0.07874015748031579 50.14313047118674 7.535442502244621 -0.1968503937007863 43.55703534344437 7.535442502244626 -0.1968503937007866 50.14313047118674 7.535442502244621 0.07874015748031607 50.14313047118665 2.958555403999804 -0.1968503937007863 50.14313047118665 2.958555403999804 0.07874015748031607 43.53651592631481 7.531360936406135 0.07874015748031579 43.55703534344437 7.535442502244626 -0.1968503937007866 43.53651592631481 7.531360936406135 -0.1968503937007866 43.55703534344437 7.535442502244626 0.07874015748031579 50.14313047118665 2.958555403999804 0.07874015748031607 43.58301713362136 2.958555403999797 -0.1968503937007863 50.14313047118665 2.958555403999804 -0.1968503937007863 43.58301713362136 2.958555403999797 0.07874015748031607 43.51563182539531 7.524271739406478 0.07874015748031579 43.51563182539531 7.524271739406478 -0.1968503937007866 43.58301713362136 2.958555403999797 0.07874015748031607 43.55988397405696 2.960071631383501 -0.1968503937007863 43.58301713362136 2.958555403999797 -0.1968503937007863 43.55988397405696 2.960071631383501 0.07874015748031607 43.49585171674453 7.514517269298941 0.07874015748031579 43.49585171674453 7.514517269298941 -0.1968503937007866 43.53825321362565 2.964374257149114 -0.1968503937007863 43.53825321362565 2.964374257149114 0.07874015748031607 43.47751404350557 7.502264427771523 0.07874015748031579 43.47751404350557 7.502264427771523 -0.1968503937007866 43.51736911270614 2.971463454148768 -0.1968503937007863 43.51736911270614 2.971463454148768 0.07874015748031607 43.46093256835167 7.487722864339863 0.07874015748031579 43.46093256835167 7.487722864339863 -0.1968503937007866 43.49758900405537 2.981217924256313 -0.1968503937007863 43.49758900405537 2.981217924256313 0.07874015748031607 43.44639100492 7.47114138918596 -0.1968503937007866 43.44639100492 7.47114138918596 0.07874015748031579 43.47925133081637 2.993470765783733 -0.1968503937007863 43.47925133081637 2.993470765783733 0.07874015748031607 43.4341381633926 7.452803715947015 -0.1968503937007866 43.4341381633926 7.452803715947015 0.07874015748031579 43.46266985566252 3.008012329215369 -0.1968503937007863 43.46266985566252 3.008012329215369 0.07874015748031607 43.42438369328506 7.43302360729623 -0.1968503937007866 43.42438369328506 7.43302360729623 0.07874015748031579 43.44812829223088 3.024593804369232 0.07874015748031607 43.44812829223088 3.024593804369232 -0.1968503937007863 43.41729449628541 7.412139506376729 -0.1968503937007866 43.41729449628541 7.412139506376729 0.07874015748031579 43.43587545070344 3.042931477608274 0.07874015748031607 43.43587545070344 3.042931477608274 -0.1968503937007863 43.4132129304469 7.39162008924713 -0.1968503937007866 43.4132129304469 7.39162008924713 0.07874015748031579 43.4261209805959 3.062711586259032 0.07874015748031607 43.4261209805959 3.062711586259032 -0.1968503937007863 43.4132129304469 7.39162008924713 0.07874015748031579 43.4132129304469 3.128359607174164 -0.1968503937007863 43.4132129304469 3.128359607174164 0.07874015748031607 43.4132129304469 7.39162008924713 -0.1968503937007866 43.41903178359623 3.083595687178518 0.07874015748031607 43.41903178359623 3.083595687178518 -0.1968503937007863 43.4132129304469 3.128359607174164 0.07874015748031607 43.41472915783061 3.105226447609857 -0.1968503937007863 43.41472915783061 3.105226447609857 0.07874015748031607 43.4132129304469 3.128359607174164 -0.1968503937007863 + + + + + + + + + + 0.9914448613738508 0.1305261922197449 1.55246491908785e-017 0.9978589232385636 0.06540312923075399 1.759089571435054e-017 0.9978589232385636 0.06540312923075399 1.759089571435054e-017 0.9914448613738508 0.1305261922197449 1.55246491908785e-017 1 0 1.95818153218181e-017 1 0 1.95818153218181e-017 1 0 1.95818153218181e-017 1 0 1.95818153218181e-017 0.9659258262890319 0.2588190451026562 1.12018520080126e-017 0.9659258262890319 0.2588190451026562 1.12018520080126e-017 0.9978589232385156 -0.06540312923148701 2.148888258984201e-017 0.9914448613737552 -0.1305261922204699 2.330393116351783e-017 0.9914448613737552 -0.1305261922204699 2.330393116351783e-017 0.9978589232385156 -0.06540312923148701 2.148888258984201e-017 0.9238795325111466 0.3826834323654281 6.687388031556006e-018 0.9238795325111466 0.3826834323654281 6.687388031556006e-018 0.9659258262891463 -0.2588190451022301 2.66273102819097e-017 0.9659258262891463 -0.2588190451022301 2.66273102819097e-017 0.8660254037845753 0.4999999999997635 2.058500991815655e-018 0.8660254037845753 0.4999999999997635 2.058500991815655e-018 0.9238795325113448 -0.3826834323649499 2.949508873891546e-017 0.9238795325113448 -0.3826834323649499 2.949508873891546e-017 0.7933533402911205 0.60876142900887 -2.605607570657765e-018 0.7933533402911205 0.60876142900887 -2.605607570657765e-018 0.866025403784477 -0.4999999999999336 3.18581980500125e-017 0.866025403784477 -0.4999999999999336 3.18581980500125e-017 0.7071067811863823 0.707106781186713 -7.225133465171492e-018 0.7071067811863823 0.707106781186713 -7.225133465171492e-018 0.7933533402914658 -0.6087614290084201 3.367620475970759e-017 0.7933533402914658 -0.6087614290084201 3.367620475970759e-017 0.608761429008534 0.7933533402913785 -1.172103532290912e-017 0.608761429008534 0.7933533402913785 -1.172103532290912e-017 0.7071067811870996 -0.7071067811859956 3.491800226915812e-017 0.7071067811870996 -0.7071067811859956 3.491800226915812e-017 0.5000000000000008 0.8660254037844382 -1.601638701657927e-017 0.5000000000000008 0.8660254037844382 -1.601638701657927e-017 0.6087614290086063 -0.793353340291323 3.556234307869128e-017 0.6087614290086063 -0.793353340291323 3.556234307869128e-017 0.3826834323652957 0.9238795325112014 -2.003769388781576e-017 0.3826834323652957 0.9238795325112014 -2.003769388781576e-017 0.4999999999993188 -0.8660254037848321 3.559820233839578e-017 0.4999999999993188 -0.8660254037848321 3.559820233839578e-017 0.2588190451024929 0.9659258262890758 -2.371615026114718e-017 0.2588190451024929 0.9659258262890758 -2.371615026114718e-017 0.3826834323655604 -0.9238795325110919 3.502496648641106e-017 0.3826834323655604 -0.9238795325110919 3.502496648641106e-017 0.1305261922199533 0.9914448613738235 -2.698881672814551e-017 0.1305261922199533 0.9914448613738235 -2.698881672814551e-017 0.2588190451029568 -0.9659258262889514 3.385244374708522e-017 0.2588190451029568 -0.9659258262889514 3.385244374708522e-017 0.06540312923029935 0.9978589232385934 -2.845518162128279e-017 0.06540312923029935 0.9978589232385934 -2.845518162128279e-017 0.1305261922198004 -0.9914448613738436 3.210069630956563e-017 0.1305261922198004 -0.9914448613738436 3.210069630956563e-017 8.091396214053001e-016 1 -2.979969705820778e-017 8.091396214053001e-016 1 -2.979969705820778e-017 8.091396214053001e-016 1 -2.979969705820778e-017 8.091396214053001e-016 1 -2.979969705820778e-017 0.06540312923028356 -0.9978589232385944 3.101660561739596e-017 0.06540312923028356 -0.9978589232385944 3.101660561739596e-017 -0.2588190451025151 0.9659258262890699 -3.385244374708009e-017 -0.1950903220161407 0.980785280403228 -3.304732689195967e-017 -0.2588190451025151 0.9659258262890699 -3.385244374708009e-017 -0.1950903220161407 0.980785280403228 -3.304732689195967e-017 1.015430344717675e-015 -1 2.979969705820782e-017 1.015430344717675e-015 -1 2.979969705820782e-017 1.015430344717675e-015 -1 2.979969705820782e-017 1.015430344717675e-015 -1 2.979969705820782e-017 -0.3826834323650787 0.9238795325112913 -3.502496648640756e-017 -0.3826834323650787 0.9238795325112913 -3.502496648640756e-017 -0.06540312922995281 -0.9978589232386161 2.845518162129025e-017 -0.1305261922199476 -0.9914448613738243 2.698881672814565e-017 -0.06540312922995281 -0.9978589232386161 2.845518162129025e-017 -0.1305261922199476 -0.9914448613738243 2.698881672814565e-017 -0.5000000000000135 0.8660254037844308 -3.559820233839744e-017 -0.5000000000000135 0.8660254037844308 -3.559820233839744e-017 -0.2588190451023761 -0.9659258262891071 2.371615026115041e-017 -0.2588190451023761 -0.9659258262891071 2.371615026115041e-017 -0.6087614290087011 0.7933533402912499 -3.556234307869096e-017 -0.6087614290087011 0.7933533402912499 -3.556234307869096e-017 -0.3826834323652421 -0.9238795325112237 2.003769388781746e-017 -0.3826834323652421 -0.9238795325112237 2.003769388781746e-017 -0.7071067811865318 0.7071067811865633 -3.491800226916392e-017 -0.7071067811865318 0.7071067811865633 -3.491800226916392e-017 -0.4999999999998345 -0.8660254037845342 1.60163870165854e-017 -0.4999999999998345 -0.8660254037845342 1.60163870165854e-017 -0.7933533402912634 0.6087614290086838 -3.367620475971148e-017 -0.7933533402912634 0.6087614290086838 -3.367620475971148e-017 -0.6087614290084824 -0.7933533402914178 1.172103532291131e-017 -0.6087614290084824 -0.7933533402914178 1.172103532291131e-017 -0.8660254037844439 0.4999999999999909 -3.185819805001356e-017 -0.8660254037844439 0.4999999999999909 -3.185819805001356e-017 -0.7071067811866187 -0.7071067811864763 7.225133465159809e-018 -0.7071067811866187 -0.7071067811864763 7.225133465159809e-018 -0.9238795325113307 0.382683432364984 -2.94950887389162e-017 -0.9238795325113307 0.382683432364984 -2.94950887389162e-017 -0.7933533402916141 -0.6087614290082266 2.605607570628924e-018 -0.7933533402916141 -0.6087614290082266 2.605607570628924e-018 -0.9659258262890716 0.2588190451025084 -2.662731028191653e-017 -0.9659258262890716 0.2588190451025084 -2.662731028191653e-017 -0.8660254037845783 -0.4999999999997583 -2.058500991815872e-018 -0.8660254037845783 -0.4999999999997583 -2.058500991815872e-018 -0.9807852804031837 0.1950903220163633 -2.501918872628857e-017 -0.9807852804031837 0.1950903220163633 -2.501918872628857e-017 -0.9238795325109536 -0.382683432365894 -6.687388031538348e-018 -0.9238795325109536 -0.382683432365894 -6.687388031538348e-018 -1 -1.274856552025012e-033 -1.95818153218181e-017 -1 -1.274856552025012e-033 -1.95818153218181e-017 -1 -1.274856552025012e-033 -1.95818153218181e-017 -1 -1.274856552025012e-033 -1.95818153218181e-017 -0.9659258262890079 -0.2588190451027462 -1.120185200800945e-017 -0.9659258262890079 -0.2588190451027462 -1.120185200800945e-017 -0.9978589232385796 -0.0654031292305077 -1.759089571435819e-017 -0.9914448613738123 -0.130526192220036 -1.552464919086907e-017 -0.9914448613738123 -0.130526192220036 -1.552464919086907e-017 -0.9978589232385796 -0.0654031292305077 -1.759089571435819e-017 + + + + + + + + + + + + + + +

0 1 2 1 0 3 4 5 6 5 4 7 8 3 0 3 8 9 10 11 12 11 10 13 14 9 8 9 14 15 12 16 17 16 12 11 18 15 14 15 18 19 17 20 21 20 17 16 22 19 18 19 22 23 21 24 25 24 21 20 26 23 22 23 26 27 25 28 29 28 25 24 30 26 31 26 30 27 29 32 33 32 29 28 34 31 35 31 34 30 32 36 33 36 32 37 38 35 39 35 38 34 37 40 36 40 37 41 42 39 43 39 42 38 41 44 40 44 41 45 46 43 47 43 46 42 45 48 44 48 45 49 50 47 51 47 50 46 49 52 48 52 49 53 54 55 56 55 54 57 53 58 52 58 53 59 60 61 62 61 60 63 64 65 66 65 64 67 68 62 69 62 68 60 70 71 72 71 70 73 74 69 75 69 74 68 73 76 71 76 73 77 78 75 79 75 78 74 77 80 76 80 77 81 82 79 83 79 82 78 81 84 80 84 81 85 82 86 87 86 82 83 85 88 84 88 85 89 87 90 91 90 87 86 89 92 88 92 89 93 91 94 95 94 91 90 96 92 93 92 96 97 95 98 99 98 95 94 100 97 96 97 100 101 99 102 103 102 99 98 104 101 100 101 104 105 106 107 108 107 106 109 110 105 104 105 110 111 112 113 114 113 112 115 114 111 110 111 114 113

+
+
+
+ + + + 0 0 2.165354330708662 0.1184986753859656 0.2465682045726894 2.165354330708662 0 7.874015748031497 2.165354330708662 0.119594327961949 0.2298517765885317 2.165354330708662 0.1228625387705518 0.2134213713218521 2.165354330708662 0.1282473878187189 0.1975581175621329 2.165354330708662 0.1356567388462747 0.1825334399793274 2.165354330708662 0.1449638158028776 0.1686044149725052 2.165354330708662 0.1560093720213896 0.1560093720213882 2.165354330708662 0.1686044149725068 0.1449638158028763 2.165354330708662 0.1825334399793289 0.1356567388462739 2.165354330708662 0.197558117562134 0.1282473878187185 2.165354330708662 0.2134213713218537 0.1228625387705514 2.165354330708662 0.2298517765885331 0.1195943279619491 2.165354330708662 0.2465682045726913 0.1184986753859656 2.165354330708662 51.18110236220473 0 2.165354330708662 30.0860261920037 0.1184986753859688 2.165354330708662 30.09803909744245 0.1212016043046447 2.165354330708662 30.70679771243117 0.1184986753859656 2.165354330708662 30.10330938016302 0.1244567554178949 2.165354330708662 30.10773656538716 0.1287894127682915 2.165354330708662 30.11110468898 0.1339882234195986 2.165354330708662 30.11324944927784 0.1397995822959414 2.165354330708662 30.11406622194742 0.145940003383379 2.165354330708662 51.06260368681876 0.1184986753859656 2.165354330708662 51.06260368681876 7.755517072645532 2.165354330708662 0.1184986753859656 7.755517072645532 2.165354330708662 51.18110236220473 7.874015748031497 2.165354330708662 0.1184986753859656 2.43930318405221 2.165354330708662 0.1184986753859656 2.804370064010866 2.165354330708662 0.1195943279619488 2.456019612036368 2.165354330708662 0.1228625387705512 2.472450017303047 2.165354330708662 0.1282473878187184 2.488313271062767 2.165354330708662 0.1356567388462739 2.503337948645572 2.165354330708662 0.1449638158028762 2.517266973652394 2.165354330708662 0.1560093720213884 2.529862016603511 2.165354330708662 0.1686044149725052 2.540907572822023 2.165354330708662 0.1825334399793273 2.550214649778626 2.165354330708662 0.1975581175621327 2.557624000806182 2.165354330708662 0.213421371321852 2.563008849854349 2.165354330708662 0.2298517765885315 2.566277060662952 2.165354330708662 0.2465682045726894 2.567372713238935 2.165354330708662 25.61991398185795 2.804370064010866 2.165354330708662 25.56118838034679 2.567372713238936 2.165354330708662 30.09912146437194 0.1713469183847506 2.165354330708662 30.10848249331568 0.1633477397435226 2.165354330708662 30.11162315591949 0.1580084394959358 2.165354330708662 30.11351516370367 0.1521099485644012 2.165354330708662 0 7.874015748031497 2.165354330708662 0 0 0 0 0 2.165354330708662 0 7.874015748031497 0 51.18110236220473 0 2.165354330708662 0 0 0 51.18110236220473 0 0 0 0 2.165354330708662 51.18110236220473 0 0 51.18110236220473 0.7153153851313135 0.604869657207319 51.18110236220473 0 2.165354330708662 51.18110236220473 7.874015748031497 0 51.18110236220473 7.182685229005588 0.604869657207319 51.18110236220473 0.7153153851313138 1.166727690057971 51.18110236220473 7.874015748031497 2.165354330708662 51.18110236220473 7.182685229005587 1.166727690057971 0 7.874015748031497 2.165354330708662 51.18110236220473 7.874015748031497 0 0 7.874015748031497 0 51.18110236220473 7.874015748031497 2.165354330708662 0 7.874015748031497 0 0.346039204183232 7.209720004747907 1.256040330056125e-015 0 0 0 0.3542852686363268 7.272355082731298 1.256040330056125e-015 0.3784615063303982 7.330721683659481 1.256040330056125e-015 0.4169203466197171 7.380842220134569 1.256040330056125e-015 0.4670408830948051 7.419301060423888 1.256040330056125e-015 0.525407484022988 7.443477298117959 1.256040330056125e-015 0.5880425620063782 7.451723362571054 1.256040330056125e-015 51.18110236220473 7.874015748031497 0 0.3460392041832313 0.5491086559751139 1.110223024625157e-015 0.3460392041832319 2.136762732649793 1.110223024625157e-015 0.6506776399897686 7.443477298117959 1.256040330056125e-015 0.7090442409179513 7.419301060423888 1.256040330056125e-015 0.7591647773930393 7.380842220134569 1.256040330056125e-015 0.7976236176823582 7.330721683659481 1.256040330056125e-015 0.8217998553764297 7.272355082731298 1.256040330056125e-015 0.8300459198295244 7.209720004747907 1.256040330056125e-015 43.55364811608248 7.569833598791506 8.326672684688674e-016 0.8300459198295258 3.173087089051805 5.549316253182147e-016 43.52759575677882 7.56465146232659 8.326672684688674e-016 25.50480608586854 2.339832184441669 1.110223024625157e-015 43.50244268356087 7.556113144499255 8.326672684688674e-016 43.47861927248514 7.544364738294798 8.326672684688674e-016 43.45653314872024 7.529607262200647 8.326672684688674e-016 43.43656221196721 7.512093220724323 8.326672684688674e-016 43.41904817049088 7.492122283971291 8.326672684688674e-016 43.40429069439674 7.470036160206389 8.326672684688674e-016 43.39254228819227 7.446212749130662 8.326672684688674e-016 43.38400397036494 7.421059675912715 8.326672684688674e-016 43.37882183390003 7.395007316609055 8.326672684688674e-016 50.144256319116 7.569833598791506 1.090510587941475e-015 50.1707622014146 7.568096311480678 1.090510587941475e-015 50.19681456071828 7.562914175015767 1.090510587941475e-015 50.22196763393622 7.554375857188427 1.090510587941475e-015 50.24579104501194 7.542627450983966 1.090510587941475e-015 50.26787716877683 7.527869974889834 1.090510587941475e-015 50.28784810552988 7.510355933413502 1.090510587941475e-015 50.3053621470062 7.490384996660477 1.090510587941475e-015 50.32011962310036 7.468298872895575 1.118266163557104e-015 50.3318680293048 7.44447546181984 1.118266163557104e-015 50.34040634713218 7.419322388601879 1.118266163557104e-015 50.34558848359706 7.393270029298235 1.118266163557104e-015 50.3473257709079 7.366764146999632 1.118266163557104e-015 50.3473257709079 3.127233759244805 1.103017739216966e-015 50.3473257709079 2.136762732649773 1.110223024625157e-015 50.3473257709079 0.5508869384357039 1.110223024625157e-015 0.5491086559751147 0.346039204183232 1.110223024625157e-015 51.18110236220473 0 0 0.5226027736765072 0.3477764914940557 1.110223024625157e-015 0.4965504143728469 0.3529586279589738 1.110223024625157e-015 0.4713973411549005 0.3614969457863064 1.110223024625157e-015 0.4475739300791731 0.3732453519907652 1.110223024625157e-015 0.4254878063142707 0.3880028280849154 1.110223024625157e-015 0.4055168695612388 0.4055168695612393 1.110223024625157e-015 0.3880028280849136 0.4254878063142707 1.110223024625157e-015 0.3732453519907644 0.4475739300791728 1.110223024625157e-015 0.361496945786306 0.4713973411548998 1.110223024625157e-015 0.352958627958972 0.4965504143728474 1.110223024625157e-015 0.3477764914940549 0.5226027736765067 1.110223024625157e-015 28.98669970978262 0.3460392041831966 1.110223024625157e-015 29.00270410638306 0.3478174866438403 1.110223024625157e-015 50.14425631911605 0.3478174866438403 1.110223024625157e-015 50.17076220141466 0.3495547739546495 1.110223024625157e-015 50.19681456071831 0.35473691041958 1.110223024625157e-015 50.22196763393623 0.3632752282469015 1.110223024625157e-015 50.24579104501201 0.3750236344513794 1.110223024625157e-015 50.26787716877686 0.3897811105455421 1.110223024625157e-015 50.28784810552991 0.407295152021843 1.110223024625157e-015 50.30536214700624 0.4272660887748815 1.110223024625157e-015 50.32011962310041 0.4493522125397739 1.110223024625157e-015 50.33186802930485 0.4731756236154915 1.110223024625157e-015 50.3404063471322 0.498328696833425 1.110223024625157e-015 50.34558848359711 0.5243810561371139 1.110223024625157e-015 43.55538540339332 2.925901594763743 1.109463768595622e-015 50.14425631911605 2.339832184441669 1.110223024625157e-015 43.52933304408965 2.931083731228659 1.109462778393509e-015 43.5041799708717 2.939622049055988 1.109231021428294e-015 43.480356559796 2.951370455260453 1.108772463125903e-015 43.45827043603106 2.96612793135459 1.108094949546031e-015 43.43829949927805 2.98364197283092 1.107210073133866e-015 43.42078545780171 3.003612909583954 1.106132974370159e-015 43.4060279817076 3.025699033348864 1.104882082713383e-015 43.39427957550313 3.04952244442458 1.1034788012666e-015 43.38574125767577 3.074675517642528 1.101947140564425e-015 43.38055912121086 3.10072787694619 1.100313307746131e-015 43.37882183390003 3.127233759244795 1.098605258144222e-015 43.58189128569192 2.924164307452924 1.109233975091996e-015 50.14425631911599 2.924164307452924 1.117398622990049e-015 50.17076220141464 2.925901594763754 1.118280362204888e-015 50.17076220141468 2.338094897130827 1.110223024625157e-015 50.19681456071832 2.931083731228657 1.118760003154504e-015 50.19681456071832 2.332912760665919 1.110223024625157e-015 50.22196763393622 2.939622049056019 1.118829339049262e-015 50.22196763393626 2.324374442838587 1.110223024625157e-015 50.24579104501196 2.951370455260466 1.11848718353279e-015 50.24579104501199 2.312626036634129 1.110223024625157e-015 50.26787716877688 2.966127931354595 1.11773939098083e-015 50.26787716877689 2.297868560539985 1.110223024625157e-015 50.28784810552991 2.98364197283095 1.116598756331273e-015 50.28784810552993 2.280354519063654 1.110223024625157e-015 50.3053621470062 3.003612909583975 1.115084796159225e-015 50.30536214700626 2.260383582310614 1.110223024625157e-015 50.32011962310035 3.025699033348873 1.113223414742969e-015 50.32011962310039 2.238297458545719 1.110223024625157e-015 50.33186802930481 3.049522444424608 1.111046460834616e-015 50.33186802930484 2.214474047469999 1.110223024625157e-015 50.34040634713214 3.074675517642548 1.108591182719098e-015 50.34040634713219 2.189320974252057 1.110223024625157e-015 50.34558848359704 3.100727876946217 1.105899590885709e-015 50.34558848359709 2.163268614948385 1.110223024625157e-015 0.3460392041832334 3.173087089051805 5.549316253182147e-016 0.3477764914940558 2.163268614948401 1.110223024625157e-015 0.354285268636328 3.110452011068415 5.549316253182147e-016 0.3529586279589722 2.189320974252061 1.110223024625157e-015 0.3614969457863068 2.214474047470008 1.110223024625157e-015 0.3784615063303993 3.052085410140232 5.549316253182147e-016 0.3732453519907648 2.238297458545735 1.110223024625157e-015 0.3880028280849145 2.260383582310638 1.110223024625157e-015 0.4169203466197183 3.001964873665144 5.549316253182147e-016 0.4055168695612396 2.280354519063669 1.110223024625157e-015 0.4254878063142705 2.297868560539994 1.110223024625157e-015 0.4670408830948064 2.963506033375825 5.549316253182147e-016 0.4475739300791732 2.312626036634144 1.110223024625157e-015 0.4713973411548998 2.324374442838602 1.110223024625157e-015 0.525407484022989 2.939329795681753 5.549316253182147e-016 0.4965504143728471 2.332912760665936 1.110223024625157e-015 0.5226027736765068 2.338094897130853 1.110223024625157e-015 0.5491086559751146 2.339832184441677 1.110223024625157e-015 0.5880425620063796 2.931083731228659 5.549316253182147e-016 0.6506776399897698 2.939329795681753 5.549316253182147e-016 0.7090442409179527 2.963506033375825 5.549316253182147e-016 0.7591647773930408 3.001964873665144 5.549316253182147e-016 0.7976236176823597 3.052085410140232 5.549316253182147e-016 0.8217998553764312 3.110452011068415 5.549316253182147e-016 + + + + + + + + + + 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 -0 1 0 -0 1 0 -0 1 0 -0 1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 + + + + + + + + + + + + + + +

0 1 2 1 0 3 3 0 4 4 0 5 5 0 6 6 0 7 7 0 8 8 0 9 9 0 10 10 0 11 11 0 12 12 0 13 13 0 14 14 0 15 14 15 16 16 15 17 17 15 18 17 18 19 19 18 20 20 18 21 21 18 22 22 18 23 18 15 24 24 15 25 2 26 27 26 2 1 26 1 28 26 28 29 27 26 25 27 25 15 30 29 28 29 30 31 29 31 32 29 32 33 29 33 34 29 34 35 29 35 36 29 36 37 29 37 38 29 38 39 29 39 40 29 40 41 29 41 42 42 41 43 42 43 44 42 44 18 18 44 45 18 45 46 18 46 47 18 47 23 48 49 50 49 48 51 52 53 54 53 52 55 56 57 58 57 56 59 57 59 60 58 61 62 61 58 57 62 61 63 62 63 60 62 60 59 64 65 66 65 64 67 68 69 70 69 68 71 71 68 72 72 68 73 73 68 74 74 68 75 75 68 76 76 68 77 70 69 78 78 69 79 76 77 80 80 77 81 81 77 82 82 77 83 83 77 84 84 77 85 85 77 86 85 86 87 87 86 88 87 88 89 89 88 90 89 90 91 89 91 92 89 92 93 89 93 94 89 94 95 89 95 96 89 96 97 89 97 98 86 77 99 99 77 100 100 77 101 101 77 102 102 77 103 103 77 104 104 77 105 105 77 106 106 77 107 107 77 108 108 77 109 109 77 110 110 77 111 111 77 112 112 77 113 113 77 114 70 115 116 115 70 117 117 70 118 118 70 119 119 70 120 120 70 121 121 70 122 122 70 123 123 70 124 124 70 125 125 70 126 126 70 127 127 70 78 116 115 128 116 128 129 116 129 130 116 130 131 116 131 132 116 132 133 116 133 134 116 134 135 116 135 136 116 136 137 116 137 138 116 138 139 116 139 140 116 140 141 116 141 114 116 114 77 89 142 143 142 89 144 144 89 145 145 89 146 146 89 147 147 89 148 148 89 149 149 89 150 150 89 151 151 89 152 152 89 153 153 89 154 154 89 98 143 142 155 143 155 156 143 156 157 143 157 158 158 157 159 158 159 160 160 159 161 160 161 162 162 161 163 162 163 164 164 163 165 164 165 166 166 165 167 166 167 168 168 167 169 168 169 170 170 169 171 170 171 172 172 171 173 172 173 174 174 173 175 174 175 176 176 175 177 176 177 178 178 177 112 178 112 113 179 180 79 180 179 181 180 181 182 182 181 183 183 181 184 183 184 185 185 184 186 186 184 187 186 187 188 188 187 189 189 187 190 189 190 191 191 190 192 192 190 193 192 193 194 194 193 195 195 193 196 196 193 197 196 197 89 89 197 198 89 198 199 89 199 200 89 200 201 89 201 202 89 202 87 179 79 69

+
+
+
+ + + + 0.6470483783510791 7.225530565586209 -0.2337572933700505 0.590059644476194 7.209179529129053 -0.2420033578231444 0.5880425620063792 7.209720004747907 -0.2417307881423126 0.6506776399897661 7.197963586567997 -0.2337572933700505 0.5880425620063748 7.193858266663263 -0.2420033578231444 0.7039126674564964 7.240767305930175 -0.209581055675979 0.7090442409179504 7.201789135705585 -0.209581055675979 0.5880425620063785 3.188948827136449 -0.2420033578231452 0.6506776399897699 3.184843507231715 -0.2337572933700513 0.7090442409179538 3.181017958094126 -0.2095810556759798 0.6919288565104798 7.269698784844964 -0.209581055675979 0.6409457296562897 7.240263662831568 -0.2337572933700505 0.752743139522957 7.253851391486414 -0.1711222153866596 0.7591647773930373 7.205074209224319 -0.1711222153866596 0.5900596444761919 3.173627564670658 -0.2420033578231452 0.6470483783510829 3.157276528213503 -0.2337572933700513 0.5880425620063792 3.173087089051805 -0.2417307881423139 0.5254074840229897 7.197963586567996 -0.2337572933700505 0.5880425620063785 3.188948827136449 -0.2420033578231452 0.5254074840229894 3.184843507231715 -0.2337572933700513 0.5880425620063748 7.193858266663263 -0.2420033578231444 0.7039126674564999 3.142039787869536 -0.2095810556759798 0.7591647773930392 3.177732884575392 -0.1711222153866604 0.6728653662742286 7.294542809015757 -0.209581055675979 0.631237817512777 7.252915260254307 -0.2337572933700505 0.7357090600596556 7.294975297149257 -0.1711222153866596 0.7976236176823564 7.20759493479274 -0.121001678911572 0.7902120785753058 7.263891163446743 -0.121001678911572 0.5290367456616765 3.157276528213502 -0.2337572933700513 0.5860254795365677 3.173627564670658 -0.2420033578231452 0.5880425620063792 3.173087089051805 -0.2417307881423139 0.4670408830948055 3.181017958094127 -0.2095810556759798 0.4670408830948049 7.201789135705584 -0.209581055675979 0.5880425620063792 7.209720004747907 -0.2417307881423126 0.5860254795365617 7.209179529129052 -0.2420033578231444 0.5290367456616767 7.225530565586209 -0.2337572933700505 0.6919288565104833 3.113108308954748 -0.2095810556759798 0.6409457296562934 3.142543430968143 -0.2337572933700513 0.7527431395229589 3.128955702313299 -0.1711222153866604 0.7976236176823581 3.175212159006971 -0.1210016789115728 0.6480213421034335 7.313606299252011 -0.209581055675979 0.6185862200900375 7.26262317239782 -0.2337572933700505 0.7086117527844502 7.33028919552598 -0.1711222153866596 0.7693027917821517 7.314370647202324 -0.121001678911572 0.8217998553764282 7.209179529129053 -0.06263507798338919 0.8137660383374742 7.270202427943571 -0.06263507798338919 0.4721724565562595 3.142039787869536 -0.2095810556759798 0.4169203466197199 3.177732884575392 -0.1711222153866604 0.4169203466197176 7.205074209224319 -0.1711222153866596 0.4721724565562592 7.240767305930176 -0.209581055675979 0.6728653662742311 3.088264284783953 -0.2095810556759798 0.6312378175127806 3.129891833545404 -0.2337572933700513 0.7357090600596575 3.087831796650455 -0.1711222153866604 0.7902120785753077 3.118915930352971 -0.1210016789115728 0.8217998553764306 3.173627564670658 -0.06263507798339002 0.6190898631886472 7.325590110198027 -0.209581055675979 0.6038531228446804 7.268725821092609 -0.2337572933700505 0.6732978544077269 7.357386502801186 -0.1711222153866596 0.7360409198764716 7.357718362618001 -0.121001678911572 0.790420694377345 7.326563073950379 -0.06263507798338919 0.8300459198295244 7.209720004747907 1.256040330056125e-015 0.8217998553764297 7.272355082731298 1.256040330056125e-015 0.4841562675022759 3.113108308954748 -0.2095810556759798 0.5351393943564656 3.142543430968144 -0.2337572933700513 0.4233419844898002 3.128955702313298 -0.1711222153866604 0.3784615063303992 7.207594934792739 -0.121001678911572 0.3784615063304005 3.175212159006972 -0.1210016789115728 0.4233419844897982 7.253851391486415 -0.1711222153866596 0.4841562675022756 7.269698784844964 -0.209581055675979 0.5351393943564662 7.240263662831568 -0.2337572933700505 0.6480213421034365 3.069200794547701 -0.2095810556759798 0.6185862200900409 3.120183921401891 -0.2337572933700513 0.7086117527844518 3.052517898273733 -0.1711222153866604 0.7693027917821532 3.068436446597388 -0.1210016789115728 0.8137660383374767 3.112604665856142 -0.06263507798339002 0.8300459198295258 3.173087089051805 5.549316253182147e-016 0.5880425620063783 7.329677564942021 -0.209581055675979 0.5880425620063781 7.270807320915229 -0.2337572933700505 0.6321739487448852 7.374420582264487 -0.1711222153866596 0.6926932044607942 7.390980234523682 -0.121001678911572 0.753283615141812 7.37496105788334 -0.06263507798338919 0.7976236176823582 7.330721683659481 1.256040330056125e-015 0.5032197577385278 3.088264284783953 -0.2095810556759798 0.5448473064999787 3.129891833545404 -0.2337572933700513 0.4403760639531013 3.087831796650455 -0.1711222153866604 0.3858730454374511 3.11891593035297 -0.1210016789115728 0.3542852686363288 7.209179529129052 -0.06263507798338919 0.3542852686363288 3.173627564670658 -0.06263507798339002 0.3858730454374499 7.263891163446743 -0.121001678911572 0.4403760639530996 7.294975297149258 -0.1711222153866596 0.5032197577385272 7.294542809015758 -0.209581055675979 0.5448473064999786 7.252915260254307 -0.2337572933700505 0.6190898631886485 3.057216983601685 -0.2095810556759798 0.6038531228446821 3.114081272707101 -0.2337572933700513 0.6732978544077288 3.025420590998527 -0.1711222153866604 0.7360409198764732 3.025088731181712 -0.1210016789115728 0.7904206943773474 3.056244019849333 -0.06263507798339002 0.8217998553764312 3.110452011068415 5.549316253182147e-016 0.5722320011680755 7.268725821092609 -0.2337572933700505 0.5569952608241093 7.325590110198028 -0.209581055675979 0.5880425620063781 7.380230589550607 -0.1711222153866596 0.6422137207052132 7.411889521316836 -0.121001678911572 0.7048856312088494 7.412098137118874 -0.06263507798338919 0.7591647773930393 7.380842220134569 1.256040330056125e-015 0.5280637819093225 3.069200794547701 -0.2095810556759798 0.5574989039227182 3.120183921401891 -0.2337572933700513 0.467473371228307 3.052517898273733 -0.1711222153866604 0.4067823322306052 3.068436446597388 -0.1210016789115728 0.3623190856752828 3.112604665856142 -0.06263507798339002 0.346039204183232 7.209720004747907 1.256040330056125e-015 0.3460392041832334 3.173087089051805 5.549316253182147e-016 0.3623190856752829 7.27020242794357 -0.06263507798338919 0.406782332230604 7.314370647202324 -0.121001678911572 0.4674733712283056 7.330289195525981 -0.1711222153866596 0.5280637819093215 7.313606299252011 -0.209581055675979 0.5574989039227177 7.26262317239782 -0.2337572933700505 0.5880425620063796 3.111999772884482 -0.2337572933700513 0.5880425620063795 3.05312952885769 -0.2095810556759798 0.6321739487448865 3.008386511535226 -0.1711222153866604 0.692693204460796 2.991826859276031 -0.1210016789115728 0.7532836151418134 3.007846035916371 -0.06263507798339002 0.7976236176823597 3.052085410140232 5.549316253182147e-016 0.5439111752678711 7.374420582264487 -0.1711222153866596 0.5880425620063783 7.41902128965674 -0.121001678911572 0.6485249852020408 7.435443481079003 -0.06263507798338919 0.7090442409179513 7.419301060423888 1.256040330056125e-015 0.5569952608241104 3.057216983601685 -0.2095810556759798 0.5722320011680768 3.114081272707101 -0.2337572933700513 0.5027872696050301 3.025420590998527 -0.1711222153866604 0.4400442041362855 3.025088731181712 -0.1210016789115728 0.3856644296354121 3.056244019849333 -0.06263507798339002 0.354285268636328 3.110452011068415 5.549316253182147e-016 0.3542852686363268 7.272355082731298 1.256040330056125e-015 0.385664429635412 7.326563073950378 -0.06263507798338919 0.4400442041362841 7.357718362618001 -0.121001678911572 0.5027872696050288 7.357386502801186 -0.1711222153866596 0.5880425620063796 3.002576504249106 -0.1711222153866604 0.6422137207052142 2.970917572482877 -0.1210016789115728 0.7048856312088514 2.970708956680837 -0.06263507798339002 0.7591647773930408 3.001964873665144 5.549316253182147e-016 0.5338714033075435 7.411889521316836 -0.121001678911572 0.5880425620063782 7.443406143152849 -0.06263507798338919 0.6506776399897686 7.443477298117959 1.256040330056125e-015 0.5439111752678723 3.008386511535226 -0.1711222153866604 0.4833919195519629 2.991826859276031 -0.1210016789115728 0.4228015088709456 3.007846035916372 -0.06263507798339002 0.3784615063303993 3.052085410140232 5.549316253182147e-016 0.3784615063303982 7.330721683659481 1.256040330056125e-015 0.4228015088709459 7.374961057883341 -0.06263507798338919 0.4833919195519614 7.390980234523682 -0.121001678911572 0.5880425620063796 2.963785804142972 -0.1210016789115728 0.6485249852020425 2.947363612720708 -0.06263507798339002 0.7090442409179527 2.963506033375825 5.549316253182147e-016 0.5275601388107158 7.435443481079003 -0.06263507798338919 0.5880425620063782 7.451723362571054 1.256040330056125e-015 0.5338714033075445 2.970917572482877 -0.1210016789115728 0.4711994928039077 2.970708956680837 -0.06263507798339002 0.4169203466197183 3.001964873665144 5.549316253182147e-016 0.4169203466197171 7.380842220134569 1.256040330056125e-015 0.4711994928039074 7.412098137118874 -0.06263507798338919 0.5880425620063796 2.939400950646861 -0.06263507798339002 0.6506776399897698 2.939329795681753 5.549316253182147e-016 0.525407484022988 7.443477298117959 1.256040330056125e-015 0.5275601388107163 2.947363612720708 -0.06263507798339002 0.4670408830948064 2.963506033375825 5.549316253182147e-016 0.4670408830948051 7.419301060423888 1.256040330056125e-015 0.5880425620063796 2.931083731228659 5.549316253182147e-016 0.525407484022989 2.939329795681753 5.549316253182147e-016 + + + + + + + + + + 0.2980469559637359 0.07455112482027697 -0.9516355089154578 0.129409522551249 0.01703708685546249 -0.9914448613738121 0.129409522551249 0.01703708685546249 -0.9914448613738121 0.2628076869683011 0.01722532585836539 -0.9646944634543336 0.1300206976615136 0.007784386697886409 -0.9914807217003017 0.487749567089461 0.1306921026102494 -0.8631453725296541 0.5022026247522211 0.03291609906116259 -0.8641232864091647 0.1300206976615145 -0.007784386697885729 -0.9914807217003016 0.2628076869683022 -0.01722532585836404 -0.9646944634543334 0.5022026247522249 -0.03291609906116251 -0.8641232864091626 0.4373042984129965 0.2524777544065234 -0.8631453725296547 0.3289889588963535 0.189941863979224 -0.925034244356603 0.6853829641193342 0.1836478117418226 -0.704644359757059 0.7075597098930087 0.04637591353493291 -0.7051301522271769 0.1294095225512511 -0.01703708685545926 -0.9914448613738118 0.2980469559637368 -0.07455112482027632 -0.9516355089154577 0.1294095225512511 -0.01703708685545926 -0.9914448613738118 -0.2628076869683021 0.01722532585836941 -0.9646944634543332 -0.1300206976615204 -0.007784386697888517 -0.9914807217003007 -0.2628076869683041 -0.01722532585836543 -0.9646944634543327 -0.1300206976615192 0.007784386697895602 -0.9914807217003009 0.4877495670894685 -0.1306921026102526 -0.8631453725296494 0.7075597098930115 -0.04637591353493292 -0.7051301522271741 0.3570574644792096 0.3570574644792076 -0.8631453725296554 0.2686183601018445 0.2686183601018439 -0.9250342443566033 0.6144975546712324 0.3547803286058008 -0.7046443597570592 0.8650724726254417 0.05669984544201129 -0.4984322869082181 0.8373882722621905 0.2243775113039457 -0.4984331589077831 -0.2980469559637379 -0.07455112482027781 -0.951635508915457 -0.1294095225512526 -0.01703708685546406 -0.9914448613738116 -0.1294095225512526 -0.01703708685546406 -0.9914448613738116 -0.5022026247522233 -0.03291609906116239 -0.8641232864091635 -0.5022026247522188 0.03291609906116216 -0.8641232864091661 -0.1294095225512497 0.0170370868554802 -0.9914448613738116 -0.1294095225512497 0.0170370868554802 -0.9914448613738116 -0.2980469559637334 0.07455112482028185 -0.9516355089154581 0.4373042984130039 -0.2524777544065295 -0.8631453725296491 0.328988958896355 -0.1899418639792258 -0.9250342443566021 0.6853829641193395 -0.1836478117418259 -0.7046443597570529 0.8650724726254407 -0.05669984544201203 -0.4984322869082199 0.2524777544065273 0.4373042984129941 -0.8631453725296547 0.1899418639792284 0.3289889588963501 -0.9250342443566034 0.5017351523775112 0.5017351523775082 -0.7046443597570581 0.7507817855914651 0.4334640660138978 -0.4984331589077823 0.9640854128455839 0.06318949640755746 -0.2579658975177134 0.9331937336188315 0.2500485073049494 -0.2581185764897834 -0.4877495670894679 -0.1306921026102518 -0.8631453725296499 -0.7075597098930101 -0.0463759135349334 -0.7051301522271755 -0.7075597098930094 0.04637591353493286 -0.7051301522271762 -0.4877495670894583 0.1306921026102496 -0.8631453725296557 0.3570574644792161 -0.3570574644792161 -0.8631453725296491 0.2686183601018471 -0.2686183601018466 -0.9250342443566016 0.6144975546712366 -0.3547803286058063 -0.7046443597570529 0.8373882722621882 -0.2243775113039466 -0.4984331589077866 0.9640854128455844 -0.06318949640755783 -0.2579658975177117 0.1306921026102529 0.4877495670894601 -0.8631453725296541 0.09832114372019474 0.3669395038220337 -0.9250342443566036 0.3547803286058044 0.6144975546712306 -0.704644359757059 0.6130107609582474 0.6130107609582429 -0.4984331589077781 0.8366786123435727 0.4830566220617641 -0.2581185764897827 0.9892858993695024 0.06484122355896389 -0.1308014718420683 0.9575208326510117 0.2565669338448132 -0.1316330638433379 -0.4373042984130037 -0.2524777544065278 -0.8631453725296495 -0.328988958896355 -0.1899418639792242 -0.9250342443566025 -0.6853829641193372 -0.1836478117418237 -0.7046443597570558 -0.865072472625448 0.05669984544201193 -0.4984322869082074 -0.8650724726254442 -0.05669984544201199 -0.4984322869082139 -0.6853829641193361 0.183647811741824 -0.7046443597570568 -0.437304298412995 0.2524777544065209 -0.8631453725296562 -0.3289889588963511 0.1899418639792211 -0.9250342443566044 0.2524777544065291 -0.4373042984130041 -0.8631453725296492 0.1899418639792263 -0.3289889588963555 -0.925034244356602 0.5017351523775135 -0.5017351523775139 -0.7046443597570524 0.750781785591461 -0.4334640660138997 -0.4984331589077866 0.9331937336188322 -0.2500485073049493 -0.2581185764897809 0.9892858993695034 -0.06484122355896398 -0.1308014718420602 1.481513538301518e-016 0.5049555088130492 -0.8631453725296537 2.833507410527474e-016 0.3798837279584447 -0.9250342443566046 0.1836478117418217 0.6853829641193345 -0.7046443597570591 0.4334640660139029 0.750781785591468 -0.4984331589077735 0.6831452263138832 0.6831452263138795 -0.2581185764897826 0.858489692644828 0.4956492551450112 -0.1316330638433374 -0.3570574644792166 -0.3570574644792146 -0.8631453725296495 -0.268618360101847 -0.2686183601018445 -0.9250342443566024 -0.6144975546712351 -0.3547803286058037 -0.7046443597570554 -0.8373882722621904 -0.2243775113039465 -0.4984331589077828 -0.9640854128455852 0.06318949640755761 -0.2579658975177083 -0.9640854128455854 -0.06318949640755829 -0.2579658975177077 -0.8373882722621981 0.224377511303948 -0.4984331589077693 -0.6144975546712339 0.3547803286058023 -0.7046443597570569 -0.3570574644792097 0.3570574644792061 -0.8631453725296557 -0.2686183601018436 0.2686183601018393 -0.925034244356605 0.130692102610254 -0.4877495670894688 -0.863145372529649 0.09832114372019156 -0.366939503822038 -0.9250342443566022 0.3547803286058064 -0.6144975546712369 -0.7046443597570525 0.6130107609582429 -0.6130107609582404 -0.4984331589077868 0.8366786123435729 -0.4830566220617641 -0.2581185764897814 0.9575208326510132 -0.2565669338448152 -0.1316330638433239 -0.09832114372019248 0.36693950382203 -0.9250342443566053 -0.130692102610252 0.4877495670894637 -0.8631453725296522 -5.095627254616813e-016 0.7095606572116078 -0.7046443597570559 0.2243775113039432 0.8373882722621986 -0.4984331589077709 0.483056622061765 0.8366786123435727 -0.2581185764897807 0.700953898806195 0.7009538988061976 -0.131633063843343 -0.2524777544065299 -0.4373042984130035 -0.8631453725296492 -0.1899418639792275 -0.328988958896354 -0.9250342443566021 -0.5017351523775135 -0.501735152377512 -0.7046443597570538 -0.7507817855914644 -0.4334640660138989 -0.4984331589077828 -0.9331937336188333 -0.2500485073049486 -0.2581185764897773 -0.9892858993695011 0.06484122355896468 -0.1308014718420768 -0.9892858993695026 -0.06484122355896477 -0.1308014718420667 -0.933193733618833 0.2500485073049489 -0.2581185764897785 -0.7507817855914721 0.4334640660139016 -0.4984331589077685 -0.5017351523775114 0.5017351523775091 -0.704644359757057 -0.2524777544065261 0.4373042984129952 -0.8631453725296545 -0.1899418639792249 0.3289889588963474 -0.925034244356605 3.120964684059297e-016 -0.3798837279584495 -0.9250342443566026 1.795773985820026e-016 -0.5049555088130583 -0.8631453725296484 0.1836478117418268 -0.6853829641193396 -0.7046443597570526 0.4334640660138992 -0.7507817855914616 -0.4984331589077862 0.6831452263138821 -0.683145226313881 -0.2581185764897815 0.8584896926448293 -0.4956492551450125 -0.131633063843325 -0.1836478117418218 0.6853829641193373 -0.7046443597570562 2.263559080302044e-017 0.8669281320278058 -0.4984331589077708 0.2500485073049453 0.9331937336188334 -0.2581185764897797 0.4956492551450089 0.8584896926448271 -0.1316330638433521 -0.1306921026102543 -0.4877495670894691 -0.8631453725296487 -0.09832114372019264 -0.3669395038220378 -0.9250342443566023 -0.3547803286058062 -0.6144975546712361 -0.7046443597570532 -0.6130107609582444 -0.613010760958241 -0.4984331589077842 -0.8366786123435742 -0.4830566220617643 -0.258118576489777 -0.9575208326510127 -0.2565669338448145 -0.1316330638433294 -0.9575208326510101 0.2565669338448134 -0.13163306384335 -0.8366786123435743 0.4830566220617635 -0.2581185764897779 -0.6130107609582521 0.6130107609582458 -0.498433158907769 -0.3547803286058033 0.6144975546712327 -0.7046443597570575 3.878087999088903e-016 -0.709560657211612 -0.7046443597570518 0.2243775113039441 -0.8373882722621896 -0.4984331589077854 0.4830566220617642 -0.836678612343573 -0.2581185764897814 0.7009538988061992 -0.7009538988061969 -0.1316330638433243 -0.2243775113039425 0.8373882722621988 -0.4984331589077705 -2.360456869878988e-016 0.966113244123529 -0.2581185764897802 0.2565669338448097 0.9575208326510102 -0.1316330638433568 -0.183647811741826 -0.6853829641193396 -0.7046443597570528 -0.4334640660139001 -0.7507817855914613 -0.4984331589077861 -0.6831452263138839 -0.6831452263138803 -0.2581185764897786 -0.8584896926448302 -0.4956492551450097 -0.1316330638433289 -0.8584896926448269 0.4956492551450096 -0.1316330638433514 -0.6831452263138826 0.6831452263138816 -0.2581185764897779 -0.433464066013904 0.7507817855914699 -0.4984331589077699 4.255491070967834e-016 -0.8669281320277973 -0.4984331589077857 0.2500485073049474 -0.9331937336188324 -0.2581185764897815 0.4956492551450117 -0.8584896926448298 -0.1316330638433249 -0.2500485073049449 0.9331937336188337 -0.2581185764897794 -1.801666719264949e-016 0.9912985102900188 -0.1316330638433572 -0.224377511303944 -0.8373882722621894 -0.4984331589077857 -0.4830566220617651 -0.8366786123435727 -0.2581185764897803 -0.7009538988061994 -0.7009538988061961 -0.1316330638433261 -0.7009538988061964 0.7009538988061944 -0.1316330638433522 -0.4830566220617643 0.8366786123435739 -0.2581185764897782 4.630126937070359e-016 -0.9661132441235285 -0.258118576489782 0.2565669338448128 -0.9575208326510133 -0.1316330638433277 -0.2565669338448093 0.9575208326510102 -0.1316330638433571 -0.2500485073049477 -0.9331937336188324 -0.2581185764897814 -0.4956492551450126 -0.8584896926448291 -0.1316330638433255 -0.4956492551450089 0.8584896926448268 -0.1316330638433547 4.684333470088864e-016 -0.9912985102900226 -0.1316330638433289 -0.2565669338448131 -0.9575208326510133 -0.1316330638433277 + + + + + + + + + + + + + + +

0 1 2 1 3 4 3 1 0 5 3 0 3 5 6 3 7 4 7 3 8 6 8 3 8 6 9 10 0 11 0 10 5 12 6 5 6 12 13 8 14 7 14 8 15 15 16 14 17 18 19 18 17 20 8 21 15 21 8 9 13 9 6 9 13 22 23 11 24 11 23 10 25 5 10 5 25 12 12 26 13 26 12 27 18 28 19 28 18 29 30 28 29 17 31 32 31 17 19 33 34 35 35 20 17 20 35 34 15 36 37 36 15 21 9 38 21 38 9 22 22 26 39 26 22 13 40 24 41 24 40 23 42 10 23 10 42 25 25 27 12 27 25 43 27 44 26 44 27 45 19 46 31 46 19 28 32 47 48 47 32 31 49 17 32 17 49 35 37 50 51 50 37 36 21 52 36 52 21 38 38 39 53 39 38 22 39 44 54 44 39 26 55 41 56 41 55 40 57 23 40 23 57 42 42 43 25 43 42 58 43 45 27 45 43 59 45 60 44 60 45 61 28 62 46 62 28 63 31 64 47 64 31 46 65 47 66 47 65 48 67 32 48 32 67 49 68 35 49 35 68 69 51 70 71 70 51 50 36 72 50 72 36 52 52 53 73 53 52 38 53 54 74 54 53 39 54 60 75 60 54 44 76 56 77 56 76 55 78 40 55 40 78 57 79 42 57 42 79 58 58 59 43 59 58 80 59 61 45 61 59 81 63 82 62 82 63 83 46 84 64 84 46 62 66 64 85 64 66 47 86 66 87 66 86 65 65 67 48 67 65 88 89 49 67 49 89 68 90 69 68 69 90 91 71 92 93 92 71 70 50 94 70 94 50 72 72 73 95 73 72 52 73 74 96 74 73 53 74 75 97 75 74 54 76 98 99 98 76 77 78 76 100 76 78 55 101 57 78 57 101 79 102 58 79 58 102 80 80 81 59 81 80 103 83 104 82 104 83 105 62 106 84 106 62 82 85 84 107 84 85 64 87 85 108 85 87 66 109 87 110 87 109 86 86 88 65 88 86 111 88 89 67 89 88 112 113 68 89 68 113 90 114 91 90 91 114 115 116 92 117 92 116 93 70 118 92 118 70 94 95 94 72 94 95 119 95 96 120 96 95 73 96 97 121 97 96 74 99 115 114 115 99 98 100 99 122 99 100 76 123 78 100 78 123 101 124 79 101 79 124 102 125 80 102 80 125 103 105 126 104 126 105 127 82 128 106 128 82 104 107 106 129 106 107 84 108 107 130 107 108 85 110 108 131 108 110 87 109 111 86 111 109 132 111 112 88 112 111 133 112 113 89 113 112 134 135 90 113 90 135 114 127 117 126 117 127 116 92 136 117 136 92 118 119 118 94 118 119 137 120 119 95 119 120 138 120 121 139 121 120 96 122 114 135 114 122 99 140 100 122 100 140 123 141 101 123 101 141 124 142 102 124 102 142 125 104 143 128 143 104 126 144 106 128 106 144 129 130 129 145 129 130 107 131 130 146 130 131 108 132 133 111 133 132 147 133 134 112 134 133 148 134 135 113 135 134 149 126 136 143 136 126 117 137 136 118 136 137 150 138 137 119 137 138 151 139 138 120 138 139 152 149 122 135 122 149 140 153 123 140 123 153 141 154 124 141 124 154 142 155 128 143 128 155 144 156 129 144 129 156 145 146 145 157 145 146 130 147 148 133 148 147 158 148 149 134 149 148 159 150 143 136 143 150 155 151 150 137 150 151 160 152 151 138 151 152 161 159 140 149 140 159 153 162 141 153 141 162 154 163 144 155 144 163 156 164 145 156 145 164 157 158 159 148 159 158 165 160 155 150 155 160 163 161 160 151 160 161 166 165 153 159 153 165 162 167 156 163 156 167 164 166 163 160 163 166 167

+
+
+
+ + + + 0.1184986753859656 2.804370064010866 2.24409448818898 3.802459269029596 5.211752591652259 2.24409448818898 0.1184986753859656 7.755517072645532 2.24409448818898 3.821449895399476 5.203886416651894 2.24409448818898 5.080260594255362 4.709514930755915 2.24409448818898 5.233106487032441 4.689392387225837 2.24409448818898 25.61991398185795 2.804370064010866 2.24409448818898 3.786151648463726 5.224265869022172 2.24409448818898 3.773638371093813 5.240573489588042 2.24409448818898 3.765772196093449 5.259564115957922 2.24409448818898 3.763089190289438 5.279943568328199 2.24409448818898 3.841829347769753 5.201203410847884 2.24409448818898 3.862208800140031 5.203886416651894 2.24409448818898 4.937830896481261 4.768511243258649 2.24409448818898 3.881199426509911 5.211752591652259 2.24409448818898 3.89750704707578 5.224265869022172 2.24409448818898 3.910020324445693 5.240573489588042 2.24409448818898 3.917886499446058 5.259564115957922 2.24409448818898 3.920569505250068 5.279943568328199 2.24409448818898 4.815523742237236 4.862360823532994 2.24409448818898 4.721674161962891 4.984667977777018 2.24409448818898 4.662677849460157 5.127097675551119 2.24409448818898 4.642555305930079 5.279943568328199 2.24409448818898 5.385952379809521 4.709514930755915 2.24409448818898 5.528382077583623 4.768511243258649 2.24409448818898 5.650689231827647 4.862360823532995 2.24409448818898 5.744538812101991 4.984667977777018 2.24409448818898 5.803535124604726 5.12709767555112 2.24409448818898 5.823657668134803 5.279943568328199 2.24409448818898 5.233106487032441 5.870494749430561 2.24409448818898 51.06260368681876 7.755517072645532 2.24409448818898 5.080260594255362 5.850372205900484 2.24409448818898 3.821449895399476 5.356000720004503 2.24409448818898 3.802459269029596 5.348134545004139 2.24409448818898 3.786151648463726 5.335621267634227 2.24409448818898 3.773638371093813 5.319313647068356 2.24409448818898 3.765772196093449 5.300323020698476 2.24409448818898 3.841829347769753 5.358683725808514 2.24409448818898 3.86220880014003 5.356000720004504 2.24409448818898 4.93783089648126 5.791375893397749 2.24409448818898 3.881199426509911 5.348134545004139 2.24409448818898 3.89750704707578 5.335621267634227 2.24409448818898 3.910020324445693 5.319313647068356 2.24409448818898 3.917886499446058 5.300323020698476 2.24409448818898 4.815523742237236 5.697526313123404 2.24409448818898 4.721674161962891 5.57521915887938 2.24409448818898 4.662677849460157 5.432789461105278 2.24409448818898 5.38595237980952 5.850372205900484 2.24409448818898 5.528382077583622 5.791375893397749 2.24409448818898 5.650689231827647 5.697526313123404 2.24409448818898 5.744538812101991 5.575219158879381 2.24409448818898 5.803535124604726 5.432789461105278 2.24409448818898 30.70679771243117 0.1184986753859656 2.24409448818898 51.06260368681876 0.1184986753859656 2.24409448818898 + + + + + + + + + + -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 + + + + + + + + + + + + + + +

0 1 2 1 0 3 3 0 4 4 0 5 5 0 6 2 1 7 2 7 8 2 8 9 2 9 10 3 4 11 11 4 12 12 4 13 12 13 14 14 13 15 15 13 16 16 13 17 17 13 18 18 13 19 18 19 20 18 20 21 18 21 22 5 6 23 23 6 24 24 6 25 25 6 26 26 6 27 27 6 28 2 29 30 29 2 31 31 2 32 32 2 33 33 2 34 34 2 35 35 2 36 36 2 10 31 32 37 31 37 38 31 38 39 39 38 40 39 40 41 39 41 42 39 42 43 39 43 18 39 18 44 44 18 45 45 18 46 46 18 22 30 29 47 30 47 48 30 48 49 30 49 50 30 50 51 30 51 28 30 28 6 30 6 52 30 52 53

+
+
+
+ + + + 3.765772196093449 5.259564115957922 2.204724409448823 3.765772196093449 5.300323020698476 2.204724409448823 3.763089190289438 5.279943568328199 2.204724409448823 3.773638371093813 5.240573489588042 2.204724409448823 3.773638371093813 5.319313647068356 2.204724409448823 3.786151648463726 5.224265869022172 2.204724409448823 3.786151648463726 5.335621267634227 2.204724409448823 3.802459269029596 5.348134545004139 2.204724409448823 3.802459269029596 5.211752591652259 2.204724409448823 3.821449895399476 5.203886416651894 2.204724409448823 3.821449895399476 5.356000720004503 2.204724409448823 3.841829347769753 5.201203410847884 2.204724409448823 3.841829347769753 5.358683725808514 2.204724409448823 3.862208800140031 5.203886416651894 2.204724409448823 3.86220880014003 5.356000720004504 2.204724409448823 3.881199426509911 5.348134545004139 2.204724409448823 3.881199426509911 5.211752591652259 2.204724409448823 3.89750704707578 5.224265869022172 2.204724409448823 3.89750704707578 5.335621267634227 2.204724409448823 3.910020324445693 5.240573489588042 2.204724409448823 3.910020324445693 5.319313647068356 2.204724409448823 3.917886499446058 5.259564115957922 2.204724409448823 3.917886499446058 5.300323020698476 2.204724409448823 3.920569505250068 5.279943568328199 2.204724409448823 + + + + + + + + + + 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 + + + + + + + + + + + + + + +

0 1 2 1 0 3 1 3 4 4 3 5 4 5 6 6 5 7 7 5 8 7 8 9 7 9 10 10 9 11 10 11 12 12 11 13 12 13 14 14 13 15 15 13 16 15 16 17 15 17 18 18 17 19 18 19 20 20 19 21 20 21 22 22 21 23

+
+
+
+ + + + 3.821449895399476 5.203886416651894 2.24409448818898 3.841829347769753 5.201203410847884 2.204724409448823 3.821449895399476 5.203886416651894 2.204724409448823 3.841829347769753 5.201203410847884 2.24409448818898 3.862208800140031 5.203886416651894 2.204724409448823 3.862208800140031 5.203886416651894 2.24409448818898 3.802459269029596 5.211752591652259 2.24409448818898 3.802459269029596 5.211752591652259 2.204724409448823 3.881199426509911 5.211752591652259 2.204724409448823 3.881199426509911 5.211752591652259 2.24409448818898 3.786151648463726 5.224265869022172 2.24409448818898 3.786151648463726 5.224265869022172 2.204724409448823 3.89750704707578 5.224265869022172 2.204724409448823 3.89750704707578 5.224265869022172 2.24409448818898 3.773638371093813 5.240573489588042 2.204724409448823 3.773638371093813 5.240573489588042 2.24409448818898 3.910020324445693 5.240573489588042 2.24409448818898 3.910020324445693 5.240573489588042 2.204724409448823 3.765772196093449 5.259564115957922 2.204724409448823 3.765772196093449 5.259564115957922 2.24409448818898 3.917886499446058 5.259564115957922 2.24409448818898 3.917886499446058 5.259564115957922 2.204724409448823 3.763089190289438 5.279943568328199 2.204724409448823 3.763089190289438 5.279943568328199 2.24409448818898 3.920569505250068 5.279943568328199 2.24409448818898 3.920569505250068 5.279943568328199 2.204724409448823 3.765772196093449 5.300323020698476 2.204724409448823 3.765772196093449 5.300323020698476 2.24409448818898 3.917886499446058 5.300323020698476 2.24409448818898 3.917886499446058 5.300323020698476 2.204724409448823 3.773638371093813 5.319313647068356 2.204724409448823 3.773638371093813 5.319313647068356 2.24409448818898 3.910020324445693 5.319313647068356 2.24409448818898 3.910020324445693 5.319313647068356 2.204724409448823 3.786151648463726 5.335621267634227 2.204724409448823 3.786151648463726 5.335621267634227 2.24409448818898 3.89750704707578 5.335621267634227 2.24409448818898 3.89750704707578 5.335621267634227 2.204724409448823 3.802459269029596 5.348134545004139 2.24409448818898 3.802459269029596 5.348134545004139 2.204724409448823 3.881199426509911 5.348134545004139 2.204724409448823 3.881199426509911 5.348134545004139 2.24409448818898 3.821449895399476 5.356000720004503 2.24409448818898 3.821449895399476 5.356000720004503 2.204724409448823 3.86220880014003 5.356000720004504 2.204724409448823 3.86220880014003 5.356000720004504 2.24409448818898 3.841829347769753 5.358683725808514 2.24409448818898 3.841829347769753 5.358683725808514 2.204724409448823 + + + + + + + + + + 0.2588190451025272 0.9659258262890665 0 0 0.9999999999999999 0 0.2588190451025272 0.9659258262890665 0 0 0.9999999999999999 0 -0.2588190451025272 0.9659258262890665 0 -0.2588190451025272 0.9659258262890665 0 0.5000000000000094 0.8660254037844333 0 0.5000000000000094 0.8660254037844333 0 -0.5000000000000094 0.8660254037844333 0 -0.5000000000000094 0.8660254037844333 0 0.70710678118654 0.707106781186555 0 0.70710678118654 0.707106781186555 0 -0.70710678118654 0.707106781186555 0 -0.70710678118654 0.707106781186555 0 0.8660254037844379 0.5000000000000012 0 0.8660254037844379 0.5000000000000012 0 -0.8660254037844379 0.5000000000000012 0 -0.8660254037844379 0.5000000000000012 0 0.965925826289069 0.2588190451025184 0 0.965925826289069 0.2588190451025184 0 -0.965925826289069 0.2588190451025184 0 -0.965925826289069 0.2588190451025184 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0.965925826289069 -0.2588190451025184 0 0.965925826289069 -0.2588190451025184 0 -0.965925826289069 -0.2588190451025184 0 -0.965925826289069 -0.2588190451025184 0 0.8660254037844423 -0.499999999999994 0 0.8660254037844423 -0.499999999999994 0 -0.8660254037844379 -0.5000000000000012 0 -0.8660254037844379 -0.5000000000000012 0 0.7071067811865415 -0.7071067811865536 0 0.7071067811865415 -0.7071067811865536 0 -0.70710678118654 -0.707106781186555 0 -0.70710678118654 -0.707106781186555 0 0.4999999999999865 -0.8660254037844466 0 0.4999999999999865 -0.8660254037844466 0 -0.5000000000000059 -0.8660254037844354 0 -0.5000000000000059 -0.8660254037844354 0 0.2588190451025286 -0.9659258262890662 0 0.2588190451025286 -0.9659258262890662 0 -0.2588190451025246 -0.9659258262890673 0 -0.2588190451025246 -0.9659258262890673 0 1.998761949593601e-014 -1 0 1.998761949593601e-014 -1 0 + + + + + + + + + + + + + + +

0 1 2 1 0 3 3 4 1 4 3 5 6 2 7 2 6 0 5 8 4 8 5 9 10 7 11 7 10 6 9 12 8 12 9 13 14 10 11 10 14 15 16 12 13 12 16 17 18 15 14 15 18 19 20 17 16 17 20 21 22 19 18 19 22 23 24 21 20 21 24 25 26 23 22 23 26 27 28 25 24 25 28 29 30 27 26 27 30 31 32 29 28 29 32 33 34 31 30 31 34 35 36 33 32 33 36 37 38 34 39 34 38 35 36 40 37 40 36 41 42 39 43 39 42 38 41 44 40 44 41 45 46 43 47 43 46 42 45 47 44 47 45 46

+
+
+
+ + + + 4.662677849460157 5.127097675551119 1.968503937007879 4.662677849460157 5.432789461105278 1.968503937007879 4.642555305930079 5.279943568328199 1.968503937007879 4.681987464823896 5.279943568328199 1.968503937007879 4.700766390122029 5.137303469262347 1.968503937007879 4.721674161962891 4.984667977777018 1.968503937007879 4.755823413291001 5.004384057223927 1.968503937007879 4.815523742237236 4.862360823532994 1.968503937007879 4.843406489187879 4.890243570483637 1.968503937007879 4.937830896481261 4.768511243258649 1.968503937007879 4.95754697592817 4.802660494586758 1.968503937007879 5.080260594255362 4.709514930755915 1.968503937007879 5.090466387966592 4.747603471417786 1.968503937007879 5.233106487032441 4.689392387225837 1.968503937007879 5.233106487032441 4.728824546119654 1.968503937007879 5.385952379809521 4.709514930755915 1.968503937007879 5.375746586098293 4.747603471417786 1.968503937007879 5.508665998136713 4.802660494586758 1.968503937007879 5.528382077583623 4.768511243258649 1.968503937007879 5.622806484877003 4.890243570483638 1.968503937007879 5.650689231827647 4.862360823532995 1.968503937007879 5.710389560773883 5.004384057223929 1.968503937007879 5.744538812101991 4.984667977777018 1.968503937007879 5.765446583942854 5.137303469262349 1.968503937007879 5.803535124604726 5.12709767555112 1.968503937007879 5.784225509240986 5.279943568328199 1.968503937007879 4.700766390122029 5.422583667394049 1.968503937007879 4.721674161962891 5.57521915887938 1.968503937007879 4.755823413291 5.55550307943247 1.968503937007879 4.815523742237236 5.697526313123404 1.968503937007879 4.843406489187879 5.669643566172761 1.968503937007879 4.93783089648126 5.791375893397749 1.968503937007879 4.95754697592817 5.75722664206964 1.968503937007879 5.080260594255362 5.850372205900484 1.968503937007879 5.090466387966591 5.812283665238612 1.968503937007879 5.233106487032441 5.870494749430561 1.968503937007879 5.233106487032441 5.831062590536744 1.968503937007879 5.375746586098291 5.812283665238612 1.968503937007879 5.38595237980952 5.850372205900484 1.968503937007879 5.508665998136713 5.75722664206964 1.968503937007879 5.528382077583622 5.791375893397749 1.968503937007879 5.622806484877003 5.669643566172761 1.968503937007879 5.650689231827647 5.697526313123404 1.968503937007879 5.710389560773883 5.55550307943247 1.968503937007879 5.744538812101991 5.575219158879381 1.968503937007879 5.765446583942854 5.42258366739405 1.968503937007879 5.803535124604726 5.432789461105278 1.968503937007879 5.823657668134803 5.279943568328199 1.968503937007879 + + + + + + + + + + 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 + + + + + + + + + + + + + + +

0 1 2 1 0 3 3 0 4 4 0 5 4 5 6 6 5 7 6 7 8 8 7 9 8 9 10 10 9 11 10 11 12 12 11 13 12 13 14 14 13 15 14 15 16 16 15 17 17 15 18 17 18 19 19 18 20 19 20 21 21 20 22 21 22 23 23 22 24 23 24 25 1 26 27 26 1 3 27 26 28 27 28 29 29 28 30 29 30 31 31 30 32 31 32 33 33 32 34 33 34 35 35 34 36 35 36 37 35 37 38 38 37 39 38 39 40 40 39 41 40 41 42 42 41 43 42 43 44 44 43 45 44 45 46 46 45 25 46 25 24 46 24 47

+
+
+
+ + + + 4.662677849460157 5.432789461105278 1.968503937007879 4.642555305930079 5.279943568328199 2.24409448818898 4.642555305930079 5.279943568328199 1.968503937007879 4.662677849460157 5.432789461105278 2.24409448818898 4.662677849460157 5.127097675551119 2.24409448818898 4.662677849460157 5.127097675551119 1.968503937007879 4.721674161962891 5.57521915887938 1.968503937007879 4.721674161962891 5.57521915887938 2.24409448818898 4.721674161962891 4.984667977777018 2.24409448818898 4.721674161962891 4.984667977777018 1.968503937007879 4.815523742237236 5.697526313123404 1.968503937007879 4.815523742237236 5.697526313123404 2.24409448818898 4.815523742237236 4.862360823532994 2.24409448818898 4.815523742237236 4.862360823532994 1.968503937007879 4.93783089648126 5.791375893397749 2.24409448818898 4.93783089648126 5.791375893397749 1.968503937007879 4.937830896481261 4.768511243258649 1.968503937007879 4.937830896481261 4.768511243258649 2.24409448818898 5.080260594255362 5.850372205900484 2.24409448818898 5.080260594255362 5.850372205900484 1.968503937007879 5.080260594255362 4.709514930755915 1.968503937007879 5.080260594255362 4.709514930755915 2.24409448818898 5.233106487032441 5.870494749430561 2.24409448818898 5.233106487032441 5.870494749430561 1.968503937007879 5.233106487032441 4.689392387225837 1.968503937007879 5.233106487032441 4.689392387225837 2.24409448818898 5.38595237980952 5.850372205900484 2.24409448818898 5.38595237980952 5.850372205900484 1.968503937007879 5.385952379809521 4.709514930755915 1.968503937007879 5.385952379809521 4.709514930755915 2.24409448818898 5.528382077583622 5.791375893397749 2.24409448818898 5.528382077583622 5.791375893397749 1.968503937007879 5.528382077583623 4.768511243258649 1.968503937007879 5.528382077583623 4.768511243258649 2.24409448818898 5.650689231827647 5.697526313123404 2.24409448818898 5.650689231827647 5.697526313123404 1.968503937007879 5.650689231827647 4.862360823532995 1.968503937007879 5.650689231827647 4.862360823532995 2.24409448818898 5.744538812101991 5.575219158879381 1.968503937007879 5.744538812101991 5.575219158879381 2.24409448818898 5.744538812101991 4.984667977777018 2.24409448818898 5.744538812101991 4.984667977777018 1.968503937007879 5.803535124604726 5.432789461105278 1.968503937007879 5.803535124604726 5.432789461105278 2.24409448818898 5.803535124604726 5.12709767555112 2.24409448818898 5.803535124604726 5.12709767555112 1.968503937007879 5.823657668134803 5.279943568328199 1.968503937007879 5.823657668134803 5.279943568328199 2.24409448818898 + + + + + + + + + + 0.9659258262890681 -0.2588190451025217 0 1 -3.65355505721523e-016 0 1 -3.65355505721523e-016 0 0.9659258262890681 -0.2588190451025217 0 0.9659258262890681 0.2588190451025213 0 0.9659258262890681 0.2588190451025213 0 0.8660254037844393 -0.4999999999999991 0 0.8660254037844393 -0.4999999999999991 0 0.8660254037844384 0.5000000000000006 0 0.8660254037844384 0.5000000000000006 0 0.7071067811865488 -0.7071067811865462 0 0.7071067811865488 -0.7071067811865462 0 0.7071067811865462 0.7071067811865488 0 0.7071067811865462 0.7071067811865488 0 0.4999999999999997 -0.8660254037844389 0 0.4999999999999997 -0.8660254037844389 0 0.4999999999999991 0.8660254037844393 0 0.4999999999999991 0.8660254037844393 0 0.2588190451025206 -0.9659258262890682 0 0.2588190451025206 -0.9659258262890682 0 0.2588190451025217 0.9659258262890681 0 0.2588190451025217 0.9659258262890681 0 0 -1 0 0 -1 0 3.65355505721523e-016 1 0 3.65355505721523e-016 1 0 -0.2588190451025217 -0.9659258262890681 0 -0.2588190451025217 -0.9659258262890681 0 -0.2588190451025213 0.9659258262890681 0 -0.2588190451025213 0.9659258262890681 0 -0.4999999999999991 -0.8660254037844393 0 -0.4999999999999991 -0.8660254037844393 0 -0.5000000000000027 0.8660254037844372 0 -0.5000000000000027 0.8660254037844372 0 -0.7071067811865462 -0.7071067811865488 0 -0.7071067811865462 -0.7071067811865488 0 -0.7071067811865491 0.707106781186546 0 -0.7071067811865491 0.707106781186546 0 -0.8660254037844389 -0.4999999999999997 0 -0.8660254037844389 -0.4999999999999997 0 -0.8660254037844384 0.5000000000000006 0 -0.8660254037844384 0.5000000000000006 0 -0.9659258262890682 -0.2588190451025206 0 -0.9659258262890682 -0.2588190451025206 0 -0.9659258262890681 0.2588190451025217 0 -0.9659258262890681 0.2588190451025217 0 -1 0 0 -1 0 0 + + + + + + + + + + + + + + +

0 1 2 1 0 3 2 4 5 4 2 1 6 3 0 3 6 7 5 8 9 8 5 4 10 7 6 7 10 11 9 12 13 12 9 8 14 10 15 10 14 11 12 16 13 16 12 17 18 15 19 15 18 14 17 20 16 20 17 21 22 19 23 19 22 18 21 24 20 24 21 25 26 23 27 23 26 22 25 28 24 28 25 29 30 27 31 27 30 26 29 32 28 32 29 33 34 31 35 31 34 30 33 36 32 36 33 37 34 38 39 38 34 35 40 36 37 36 40 41 39 42 43 42 39 38 44 41 40 41 44 45 43 46 47 46 43 42 47 45 44 45 47 46

+
+
+
+ + + + 4.700766390122029 5.137303469262347 2.125984251968508 4.700766390122029 5.422583667394049 2.125984251968508 4.681987464823896 5.279943568328199 2.125984251968508 4.755823413291001 5.004384057223927 2.125984251968508 4.755823413291 5.55550307943247 2.125984251968508 4.843406489187879 5.669643566172761 2.125984251968508 4.843406489187879 4.890243570483637 2.125984251968508 4.95754697592817 4.802660494586758 2.125984251968508 4.95754697592817 5.75722664206964 2.125984251968508 5.090466387966592 4.747603471417786 2.125984251968508 5.090466387966591 5.812283665238612 2.125984251968508 5.233106487032441 5.831062590536744 2.125984251968508 5.233106487032441 4.728824546119654 2.125984251968508 5.375746586098293 4.747603471417786 2.125984251968508 5.375746586098291 5.812283665238612 2.125984251968508 5.508665998136713 5.75722664206964 2.125984251968508 5.508665998136713 4.802660494586758 2.125984251968508 5.622806484877003 4.890243570483638 2.125984251968508 5.622806484877003 5.669643566172761 2.125984251968508 5.710389560773883 5.004384057223929 2.125984251968508 5.710389560773883 5.55550307943247 2.125984251968508 5.765446583942854 5.137303469262349 2.125984251968508 5.765446583942854 5.42258366739405 2.125984251968508 5.784225509240986 5.279943568328199 2.125984251968508 + + + + + + + + + + 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 + + + + + + + + + + + + + + +

0 1 2 1 0 3 1 3 4 4 3 5 5 3 6 5 6 7 5 7 8 8 7 9 8 9 10 10 9 11 11 9 12 11 12 13 11 13 14 14 13 15 15 13 16 15 16 17 15 17 18 18 17 19 18 19 20 20 19 21 20 21 22 22 21 23

+
+
+
+ + + + 4.700766390122029 5.137303469262347 2.125984251968508 4.755823413291001 5.004384057223927 1.968503937007879 4.755823413291001 5.004384057223927 2.125984251968508 4.700766390122029 5.137303469262347 1.968503937007879 4.843406489187879 4.890243570483637 1.968503937007879 4.843406489187879 4.890243570483637 2.125984251968508 4.681987464823896 5.279943568328199 2.125984251968508 4.681987464823896 5.279943568328199 1.968503937007879 4.95754697592817 4.802660494586758 2.125984251968508 4.95754697592817 4.802660494586758 1.968503937007879 4.700766390122029 5.422583667394049 2.125984251968508 4.700766390122029 5.422583667394049 1.968503937007879 5.090466387966592 4.747603471417786 2.125984251968508 5.090466387966592 4.747603471417786 1.968503937007879 4.755823413291 5.55550307943247 2.125984251968508 4.755823413291 5.55550307943247 1.968503937007879 5.233106487032441 4.728824546119654 2.125984251968508 5.233106487032441 4.728824546119654 1.968503937007879 4.843406489187879 5.669643566172761 2.125984251968508 4.843406489187879 5.669643566172761 1.968503937007879 5.375746586098293 4.747603471417786 2.125984251968508 5.375746586098293 4.747603471417786 1.968503937007879 4.95754697592817 5.75722664206964 1.968503937007879 4.95754697592817 5.75722664206964 2.125984251968508 5.508665998136713 4.802660494586758 2.125984251968508 5.508665998136713 4.802660494586758 1.968503937007879 5.090466387966591 5.812283665238612 1.968503937007879 5.090466387966591 5.812283665238612 2.125984251968508 5.622806484877003 4.890243570483638 2.125984251968508 5.622806484877003 4.890243570483638 1.968503937007879 5.233106487032441 5.831062590536744 1.968503937007879 5.233106487032441 5.831062590536744 2.125984251968508 5.710389560773883 5.004384057223929 1.968503937007879 5.710389560773883 5.004384057223929 2.125984251968508 5.375746586098291 5.812283665238612 1.968503937007879 5.375746586098291 5.812283665238612 2.125984251968508 5.765446583942854 5.137303469262349 1.968503937007879 5.765446583942854 5.137303469262349 2.125984251968508 5.508665998136713 5.75722664206964 1.968503937007879 5.508665998136713 5.75722664206964 2.125984251968508 5.784225509240986 5.279943568328199 1.968503937007879 5.784225509240986 5.279943568328199 2.125984251968508 5.622806484877003 5.669643566172761 1.968503937007879 5.622806484877003 5.669643566172761 2.125984251968508 5.765446583942854 5.42258366739405 1.968503937007879 5.765446583942854 5.42258366739405 2.125984251968508 5.710389560773883 5.55550307943247 2.125984251968508 5.710389560773883 5.55550307943247 1.968503937007879 + + + + + + + + + + -0.9659258262890681 -0.2588190451025219 0 -0.8660254037844379 -0.500000000000001 0 -0.8660254037844379 -0.500000000000001 0 -0.9659258262890681 -0.2588190451025219 0 -0.707106781186548 -0.7071067811865471 0 -0.707106781186548 -0.7071067811865471 0 -1 7.930887807125743e-016 0 -1 7.930887807125743e-016 0 -0.4999999999999981 -0.8660254037844398 0 -0.4999999999999981 -0.8660254037844398 0 -0.9659258262890688 0.2588190451025187 0 -0.9659258262890688 0.2588190451025187 0 -0.2588190451025187 -0.9659258262890688 0 -0.2588190451025187 -0.9659258262890688 0 -0.8660254037844398 0.4999999999999981 0 -0.8660254037844398 0.4999999999999981 0 -7.930887807125743e-016 -1 0 -7.930887807125743e-016 -1 0 -0.7071067811865475 0.7071067811865475 0 -0.7071067811865475 0.7071067811865475 0 0.2588190451025202 -0.9659258262890684 0 0.2588190451025202 -0.9659258262890684 0 -0.4999999999999992 0.8660254037844393 0 -0.4999999999999992 0.8660254037844393 0 0.5000000000000023 -0.8660254037844374 0 0.5000000000000023 -0.8660254037844374 0 -0.2588190451025195 0.9659258262890687 0 -0.2588190451025195 0.9659258262890687 0 0.7071067811865494 -0.7071067811865457 0 0.7071067811865494 -0.7071067811865457 0 3.920888354084637e-016 1 0 3.920888354084637e-016 1 0 0.8660254037844393 -0.4999999999999992 0 0.8660254037844393 -0.4999999999999992 0 0.2588190451025187 0.9659258262890688 0 0.2588190451025187 0.9659258262890688 0 0.9659258262890687 -0.2588190451025199 0 0.9659258262890687 -0.2588190451025199 0 0.4999999999999981 0.8660254037844398 0 0.4999999999999981 0.8660254037844398 0 1 -3.920888354084637e-016 0 1 -3.920888354084637e-016 0 0.7071067811865475 0.7071067811865475 0 0.7071067811865475 0.7071067811865475 0 0.9659258262890687 0.2588190451025195 0 0.9659258262890687 0.2588190451025195 0 0.8660254037844393 0.4999999999999992 0 0.8660254037844393 0.4999999999999992 0 + + + + + + + + + + + + + + +

0 1 2 1 0 3 2 4 5 4 2 1 6 3 0 3 6 7 8 4 9 4 8 5 10 7 6 7 10 11 12 9 13 9 12 8 14 11 10 11 14 15 16 13 17 13 16 12 18 15 14 15 18 19 20 17 21 17 20 16 18 22 19 22 18 23 24 21 25 21 24 20 23 26 22 26 23 27 28 25 29 25 28 24 27 30 26 30 27 31 32 28 29 28 32 33 31 34 30 34 31 35 36 33 32 33 36 37 35 38 34 38 35 39 40 37 36 37 40 41 39 42 38 42 39 43 44 41 40 41 44 45 42 46 47 46 42 43 47 45 44 45 47 46

+
+
+
+ + + + 49.88188976377955 7.182685229005588 0.604869657207319 49.88188976377955 0.7153153851313138 1.166727690057971 49.88188976377955 0.7153153851313135 0.604869657207319 49.88188976377955 7.182685229005587 1.166727690057971 51.18110236220473 0.7153153851313135 0.604869657207319 49.88188976377955 7.182685229005588 0.604869657207319 49.88188976377955 0.7153153851313135 0.604869657207319 51.18110236220473 7.182685229005588 0.604869657207319 51.18110236220473 7.182685229005587 1.166727690057971 49.88188976377955 7.182685229005588 0.604869657207319 51.18110236220473 7.182685229005588 0.604869657207319 49.88188976377955 7.182685229005587 1.166727690057971 51.18110236220473 7.182685229005587 1.166727690057971 49.88188976377955 0.7153153851313138 1.166727690057971 49.88188976377955 7.182685229005587 1.166727690057971 51.18110236220473 0.7153153851313138 1.166727690057971 49.88188976377955 0.7153153851313138 1.166727690057971 51.18110236220473 0.7153153851313135 0.604869657207319 49.88188976377955 0.7153153851313135 0.604869657207319 51.18110236220473 0.7153153851313138 1.166727690057971 + + + + + + + + + + 1 0 0 1 0 0 1 0 0 1 0 0 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -1 -1.580787970928972e-015 -0 -1 -1.580787970928972e-015 -0 -1 -1.580787970928972e-015 -0 -1 -1.580787970928972e-015 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 1 -3.95196992732243e-016 -0 1 -3.95196992732243e-016 -0 1 -3.95196992732243e-016 -0 1 -3.95196992732243e-016 + + + + + + + + + + + + + + +

0 1 2 1 0 3 4 5 6 5 4 7 8 9 10 9 8 11 12 13 14 13 12 15 16 17 18 17 16 19

+
+
+
+ + + + 43.3770845465892 7.368501434310447 8.326672684688674e-016 43.37882183390003 7.395007316609055 8.326672684688674e-016 + + + + + + + + + + + + + +

1 0

+
+
+
+ + + + 43.55364811608248 7.569833598791506 8.326672684688674e-016 43.58015399838109 7.571570886102331 8.326672684688674e-016 + + + + + + + + + + + + + +

1 0

+
+
+
+ + + + 51.06260368681876 0.1184986753859656 0 0 0 0 51.06260368681876 0.1184986753859656 2.165354330708662 + + + + + + + + + + + + + +

1 0 0 2

+
+
+
+ + + + 0 0 2.834645669291339 0 0 2.165354330708662 + + + + + + + + + + + + + +

1 0

+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + 0.1254901960784314 0.2117647058823529 0.2274509803921569 1 + + + + + + + + + + + 0.2431372549019608 0.3568627450980392 0.4352941176470588 1 + + + + + + + + + + + 0.6627450980392157 0.6627450980392157 0.6627450980392157 1 + + + + + + + + + + + 0 0 0 1 + + + + + + + + + + + 0.2156862745098039 0.3568627450980392 0.3843137254901961 1 + + + + + + + + + + + 0.2431372549019608 0.3568627450980392 0.4352941176470588 1 + + + 1 + + + + + + + + + + diff --git a/ros-realsense-nav/turtlebot/robot_description/meshes/sensors/r200_entire.dae b/ros-realsense-nav/turtlebot/robot_description/meshes/sensors/r200_entire.dae new file mode 100644 index 0000000000..0b1ede11d3 --- /dev/null +++ b/ros-realsense-nav/turtlebot/robot_description/meshes/sensors/r200_entire.dae @@ -0,0 +1,1256 @@ + + + + + Google SketchUp 8.0.4811 + + 2015-06-04T11:19:41Z + 2015-06-04T11:19:41Z + + Z_UP + + + + + + 1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 1 + + + + 1 0 0 -46.84458131056598 0 1 0 14.0515400898282 0 0 1 0.9848344141093338 0 0 0 1 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + -3.102368219972754 20.58757989953491 1.029987378231693 -3.106449785811256 17.18347771741038 1.029987378231693 -3.106449785811258 20.56706048240531 1.029987378231693 -3.104933558427559 17.16034455784605 1.029987378231692 -3.100630932661936 17.13871379741472 1.029987378231693 -3.095279022973103 20.60846400045442 1.029987378231693 -3.093541735662264 17.11782969649524 1.029987378231693 -3.085524552865565 20.6282441091052 1.029987378231693 -3.083787265554719 17.09804958784448 1.029987378231693 -3.073271711338159 20.64658178234414 1.029987378231693 -3.071534424027284 17.07971191460543 1.029987378231693 -3.058730147906489 20.66316325749805 1.029987378231693 -3.056992860595641 17.06313043945157 1.029987378231693 -3.042148672752597 20.6777048209297 1.029987378231693 -3.040411385441793 17.04858887601993 1.029987378231693 -3.023810999513636 20.68995766245712 1.029987378231693 -3.02207371220279 17.03633603449251 1.029987378231693 -3.004030890862851 20.69971213256466 1.029987378231693 -3.002293603552019 17.02658156438498 1.029987378231693 -2.98314678994335 20.70680132956432 1.029987378231693 -2.98140950263251 17.01949236738533 1.029987378231693 -2.962627372813793 20.71088289540281 1.029987378231693 -2.959778742201202 17.01518974161971 1.029987378231693 3.298549160620757 20.7108828954028 1.029987378231693 -2.9366455826368 17.01367351423601 1.029987378231693 3.298549160620672 17.01367351423602 1.029987378231692 3.321682320185027 17.01518974161972 1.029987378231692 3.321682320184983 20.7093666680191 1.029987378231693 3.343313080616291 20.70506404225349 1.029987378231693 3.34331308061632 17.01949236738532 1.029987378231692 3.364197181535779 20.69797484525384 1.029987378231693 3.36419718153578 17.026581564385 1.029987378231692 3.383977290186586 20.68822037514629 1.029987378231693 3.3839772901866 17.03633603449254 1.029987378231692 3.40231496342553 20.67596753361888 1.029987378231693 3.402314963425587 17.04858887601994 1.029987378231692 3.418896438579445 20.66142597018721 1.029987378231693 3.41889643857946 17.06313043945161 1.029987378231692 3.433438002011094 20.64484449503334 1.029987378231693 3.433438002011066 17.07971191460547 1.029987378231692 3.44569084353852 17.09804958784447 1.029987378231692 3.445690843538506 20.62650682179439 1.029987378231693 3.455445313646058 20.60672671314355 1.029987378231693 3.455445313646058 17.11782969649527 1.029987378231692 3.46253451064573 20.58584261222409 1.029987378231693 3.462534510645688 17.13871379741472 1.029987378231692 3.466837136411306 17.16034455784607 1.029987378231692 3.46683713641132 20.56421185179276 1.029987378231693 3.468353363795038 17.18347771741035 1.029987378231692 3.468353363795037 20.54107869222854 1.029987378231693 + + + + + + + + + + -3.291247193289321e-017 1.883877647482283e-016 -1 -3.291247193289321e-017 1.883877647482283e-016 -1 -3.291247193289321e-017 1.883877647482283e-016 -1 -3.291247193289321e-017 1.883877647482283e-016 -1 -3.291247193289321e-017 1.883877647482283e-016 -1 -3.291247193289321e-017 1.883877647482283e-016 -1 -3.291247193289321e-017 1.883877647482283e-016 -1 -3.291247193289321e-017 1.883877647482283e-016 -1 -3.291247193289321e-017 1.883877647482283e-016 -1 -3.291247193289321e-017 1.883877647482283e-016 -1 -3.291247193289321e-017 1.883877647482283e-016 -1 -3.291247193289321e-017 1.883877647482283e-016 -1 -3.291247193289321e-017 1.883877647482283e-016 -1 -3.291247193289321e-017 1.883877647482283e-016 -1 -3.291247193289321e-017 1.883877647482283e-016 -1 -3.291247193289321e-017 1.883877647482283e-016 -1 -3.291247193289321e-017 1.883877647482283e-016 -1 -3.291247193289321e-017 1.883877647482283e-016 -1 -3.291247193289321e-017 1.883877647482283e-016 -1 -3.291247193289321e-017 1.883877647482283e-016 -1 -3.291247193289321e-017 1.883877647482283e-016 -1 -3.291247193289321e-017 1.883877647482283e-016 -1 -3.291247193289321e-017 1.883877647482283e-016 -1 -3.291247193289321e-017 1.883877647482283e-016 -1 -3.291247193289321e-017 1.883877647482283e-016 -1 -3.291247193289321e-017 1.883877647482283e-016 -1 -3.291247193289321e-017 1.883877647482283e-016 -1 -3.291247193289321e-017 1.883877647482283e-016 -1 -3.291247193289321e-017 1.883877647482283e-016 -1 -3.291247193289321e-017 1.883877647482283e-016 -1 -3.291247193289321e-017 1.883877647482283e-016 -1 -3.291247193289321e-017 1.883877647482283e-016 -1 -3.291247193289321e-017 1.883877647482283e-016 -1 -3.291247193289321e-017 1.883877647482283e-016 -1 -3.291247193289321e-017 1.883877647482283e-016 -1 -3.291247193289321e-017 1.883877647482283e-016 -1 -3.291247193289321e-017 1.883877647482283e-016 -1 -3.291247193289321e-017 1.883877647482283e-016 -1 -3.291247193289321e-017 1.883877647482283e-016 -1 -3.291247193289321e-017 1.883877647482283e-016 -1 -3.291247193289321e-017 1.883877647482283e-016 -1 -3.291247193289321e-017 1.883877647482283e-016 -1 -3.291247193289321e-017 1.883877647482283e-016 -1 -3.291247193289321e-017 1.883877647482283e-016 -1 -3.291247193289321e-017 1.883877647482283e-016 -1 -3.291247193289321e-017 1.883877647482283e-016 -1 -3.291247193289321e-017 1.883877647482283e-016 -1 -3.291247193289321e-017 1.883877647482283e-016 -1 -3.291247193289321e-017 1.883877647482283e-016 -1 -3.291247193289321e-017 1.883877647482283e-016 -1 + + + + + + + + + + 0.05745126333282877 0.3812514796210169 0.05752684788539363 0.3182125503224145 0.05752684788539367 0.3808714904149132 0.05749876960051036 0.3177841584786306 0.0574190913455914 0.3173835888410134 0.05731998190690931 0.3816382222306373 0.05728780991967155 0.3169968462313932 0.05713934357158454 0.3820045205389852 0.05710717158434664 0.3166305479230459 0.0569124390988548 0.382344107080447 0.05688026711161637 0.3162909613815821 0.05664315088715719 0.382651171435149 0.05661097889991928 0.3159838970268809 0.0563360865324555 0.3829204596468463 0.05630391454521838 0.3157146088151839 0.05599649999099327 0.3831473641195763 0.05596432800375537 0.3154877043424539 0.05563020168264539 0.3833280024549011 0.05559802969540775 0.3153070660071292 0.05524345907302499 0.3834592838808207 0.05521128708578722 0.3151757845812097 0.05486346986692208 0.3835348684333853 0.0548107174481704 0.315096106326291 -0.0610842437151992 0.3835348684333852 0.05438232560438518 0.3150680280414076 -0.06108424371519763 0.3150680280414077 -0.06151263555898197 0.3150961063262912 -0.06151263555898117 0.3835067901485019 -0.06191320519659797 0.3834271118935832 -0.06191320519659851 0.3151757845812096 -0.06229994780621813 0.3832958304676636 -0.06229994780621814 0.3153070660071295 -0.06266624611456639 0.3831151921323387 -0.06266624611456667 0.3154877043424543 -0.06300583265602833 0.382888287659609 -0.0630058326560294 0.3157146088151841 -0.06331289701073045 0.3826189994479113 -0.06331289701073073 0.3159838970268817 -0.06358218522242767 0.3823119350932099 -0.06358218522242715 0.3162909613815828 -0.06380908969515778 0.3166305479230457 -0.06380908969515751 0.3819723485517479 -0.06398972803048254 0.381606050243399 -0.06398972803048256 0.3169968462313939 -0.06412100945640241 0.3812193076337794 -0.06412100945640162 0.3173835888410133 -0.06420068771132047 0.3177841584786308 -0.06420068771132073 0.3808187379961622 -0.0642287659962044 0.3182125503224139 -0.06422876599620439 0.3803903461523804 + + + + + + + + + + + + + + +

0 0 1 1 2 2 1 1 0 0 3 3 3 3 0 0 4 4 4 4 0 0 5 5 4 4 5 5 6 6 6 6 5 5 7 7 6 6 7 7 8 8 8 8 7 7 9 9 8 8 9 9 10 10 10 10 9 9 11 11 10 10 11 11 12 12 12 12 11 11 13 13 12 12 13 13 14 14 14 14 13 13 15 15 14 14 15 15 16 16 16 16 15 15 17 17 16 16 17 17 18 18 18 18 17 17 19 19 18 18 19 19 20 20 20 20 19 19 21 21 20 20 21 21 22 22 22 22 21 21 23 23 22 22 23 23 24 24 24 24 23 23 25 25 25 25 23 23 26 26 26 26 23 23 27 27 26 26 27 27 28 28 26 26 28 28 29 29 29 29 28 28 30 30 29 29 30 30 31 31 31 31 30 30 32 32 31 31 32 32 33 33 33 33 32 32 34 34 33 33 34 34 35 35 35 35 34 34 36 36 35 35 36 36 37 37 37 37 36 36 38 38 37 37 38 38 39 39 39 39 38 38 40 40 40 40 38 38 41 41 40 40 41 41 42 42 40 40 42 42 43 43 43 43 42 42 44 44 43 43 44 44 45 45 45 45 44 44 46 46 46 46 44 44 47 47 46 46 47 47 48 48 48 48 47 47 49 49

+
+
+
+ + + + 4.336521051638743 20.92591304564571 -1.22683777193248 4.336521051638743 14.42566015890243 1.226837771932479 4.336521051638743 14.42566015890243 -1.22683777193248 4.336521051638743 20.92591304564571 1.226837771932479 -3.98367628281653 14.40293559688007 1.22683777193248 -3.984575438041523 20.9259130456457 1.226837771932479 -3.984575438041523 14.41218903264742 1.226837771932479 -3.981405399448354 20.97427848831552 1.226837771932479 -3.979887768403605 14.36394702872245 1.226837771932479 -3.971949523908057 21.02181638485182 1.226837771932479 -3.968943357351909 14.31672960549691 1.226837771932479 -3.956369604072812 21.06771334866487 1.226837771932479 -3.951929466793871 14.2713446661733 1.226837771932479 -3.934932216690577 21.11118406997879 1.226837771932479 -3.929137209114053 14.22856875964652 1.226837771932479 -3.908004161403004 21.15148475269955 1.226837771932479 -3.900956566160614 14.18913379353699 1.226837771932479 -3.876046184701952 21.18792584097232 1.226837771932479 -3.867869716547619 14.15371451104827 1.226837771932479 -3.83960509642917 21.21988381767338 1.226837771932479 -3.83044278544533 14.1229169459238 1.226837771932479 -3.799304413708416 21.24681187296095 1.226837771932479 -3.78931615802163 14.0972680530416 1.226837771932479 -3.755833692394508 21.2682492603432 1.226837771932479 -3.745193522274203 14.0772066920701 1.226837771932479 -3.709936728581442 21.28382918017844 1.226837771932479 -3.698829828733795 14.06307611845755 1.226837771932479 -3.662398832045144 21.29328505571872 1.226837771932479 -3.651018373051289 14.0551181102362 1.226837771932479 -3.614033389375331 21.29645509431189 1.226837771932479 3.965979002972562 14.0551181102362 1.226837771932479 3.965979002972548 21.29645509431189 1.226837771932479 4.014344445642366 21.29328505571872 1.226837771932479 4.01434444564238 14.05828814882938 1.226837771932479 4.061882342178663 21.28382918017844 1.226837771932479 4.061882342178663 14.06774402436966 1.226837771932479 4.107779305991727 14.0833239442049 1.226837771932479 4.107779305991713 21.2682492603432 1.226837771932479 4.151250027305636 21.24681187296096 1.226837771932479 4.15125002730565 14.10476133158717 1.226837771932479 4.191550710026391 21.21988381767339 1.226837771932479 4.191550710026419 14.13168938687472 1.226837771932479 4.227991798299174 21.18792584097233 1.226837771932479 4.22799179829916 14.16364736357579 1.226837771932479 4.259949775000239 14.20008845184858 1.226837771932479 4.259949775000225 21.15148475269956 1.226837771932479 4.286877830287796 21.11118406997881 1.226837771932479 4.28687783028781 14.24038913456934 1.226837771932479 4.308315217670045 21.06771334866488 1.226837771932479 4.308315217670045 14.28385985588327 1.226837771932479 4.323895137505292 14.32975681969632 1.226837771932479 4.323895137505292 21.02181638485183 1.226837771932479 4.333351013045589 14.37729471623261 1.226837771932479 4.333351013045575 20.97427848831552 1.226837771932479 4.336521051638743 20.92591304564571 1.226837771932479 4.336521051638743 14.42566015890243 1.226837771932479 4.336521051638743 14.42566015890243 -1.22683777193248 4.333351013045589 14.37729471623261 1.226837771932479 4.333351013045589 14.37729471623261 -1.22683777193248 4.336521051638743 14.42566015890243 1.226837771932479 -3.981405399448354 20.97427848831552 -1.22683777193248 -3.984575438041523 14.41218903264742 -1.22683777193248 -3.984575438041523 20.9259130456457 -1.22683777193248 -3.979887768403605 14.36394702872245 -1.22683777193248 -3.971949523908057 21.02181638485182 -1.22683777193248 -3.968943357351909 14.31672960549691 -1.22683777193248 -3.956369604072812 21.06771334866487 -1.22683777193248 -3.951929466793871 14.2713446661733 -1.22683777193248 -3.934932216690577 21.11118406997879 -1.22683777193248 -3.929137209114053 14.22856875964652 -1.22683777193248 -3.908004161403004 21.15148475269955 -1.22683777193248 -3.900956566160614 14.18913379353699 -1.22683777193248 -3.876046184701952 21.18792584097232 -1.22683777193248 -3.867869716547619 14.15371451104827 -1.22683777193248 -3.83960509642917 21.21988381767338 -1.22683777193248 -3.83044278544533 14.1229169459238 -1.22683777193248 -3.799304413708416 21.24681187296095 -1.22683777193248 -3.78931615802163 14.0972680530416 -1.22683777193248 -3.755833692394508 21.2682492603432 -1.22683777193248 -3.745193522274203 14.0772066920701 -1.22683777193248 -3.709936728581442 21.28382918017844 -1.22683777193248 -3.698829828733795 14.06307611845755 -1.22683777193248 -3.662398832045144 21.29328505571872 -1.22683777193248 -3.651018373051289 14.0551181102362 -1.22683777193248 -3.614033389375331 21.29645509431189 -1.22683777193248 3.965979002972562 14.0551181102362 -1.22683777193248 3.965979002972548 21.29645509431189 -1.22683777193248 4.014344445642366 21.29328505571872 -1.22683777193248 4.01434444564238 14.05828814882938 -1.22683777193248 4.061882342178663 21.28382918017844 -1.22683777193248 4.061882342178663 14.06774402436966 -1.22683777193248 4.107779305991713 21.2682492603432 -1.22683777193248 4.107779305991727 14.0833239442049 -1.22683777193248 4.151250027305636 21.24681187296096 -1.22683777193248 4.15125002730565 14.10476133158717 -1.22683777193248 4.191550710026391 21.21988381767339 -1.22683777193248 4.191550710026419 14.13168938687472 -1.22683777193248 4.227991798299174 21.18792584097233 -1.22683777193248 4.22799179829916 14.16364736357579 -1.22683777193248 4.259949775000239 14.20008845184858 -1.22683777193248 4.259949775000225 21.15148475269956 -1.22683777193248 4.286877830287796 21.11118406997881 -1.22683777193248 4.28687783028781 14.24038913456934 -1.22683777193248 4.308315217670045 21.06771334866488 -1.22683777193248 4.308315217670045 14.28385985588327 -1.22683777193248 4.323895137505292 21.02181638485183 -1.22683777193248 4.323895137505292 14.32975681969632 -1.22683777193248 4.333351013045575 20.97427848831552 -1.22683777193248 4.333351013045589 14.37729471623261 -1.22683777193248 4.336521051638743 20.92591304564571 -1.22683777193248 4.336521051638743 14.42566015890243 -1.22683777193248 4.333351013045575 20.97427848831552 -1.22683777193248 4.336521051638743 20.92591304564571 1.226837771932479 4.336521051638743 20.92591304564571 -1.22683777193248 4.333351013045575 20.97427848831552 1.226837771932479 4.323895137505292 14.32975681969632 1.226837771932479 4.323895137505292 14.32975681969632 -1.22683777193248 4.323895137505292 21.02181638485183 -1.22683777193248 4.323895137505292 21.02181638485183 1.226837771932479 4.308315217670045 21.06771334866488 -1.22683777193248 4.308315217670045 21.06771334866488 1.226837771932479 4.286877830287796 21.11118406997881 -1.22683777193248 4.286877830287796 21.11118406997881 1.226837771932479 4.259949775000225 21.15148475269956 -1.22683777193248 4.259949775000225 21.15148475269956 1.226837771932479 4.227991798299174 21.18792584097233 -1.22683777193248 4.227991798299174 21.18792584097233 1.226837771932479 4.191550710026391 21.21988381767339 1.226837771932479 4.191550710026391 21.21988381767339 -1.22683777193248 4.151250027305636 21.24681187296096 1.226837771932479 4.151250027305636 21.24681187296096 -1.22683777193248 4.107779305991713 21.2682492603432 1.226837771932479 4.107779305991713 21.2682492603432 -1.22683777193248 4.061882342178663 21.28382918017844 1.226837771932479 4.061882342178663 21.28382918017844 -1.22683777193248 4.014344445642366 21.29328505571872 1.226837771932479 4.014344445642366 21.29328505571872 -1.22683777193248 3.965979002972548 21.29645509431189 1.226837771932479 3.965979002972548 21.29645509431189 -1.22683777193248 -3.614033389375331 21.29645509431189 1.226837771932479 3.965979002972548 21.29645509431189 -1.22683777193248 -3.614033389375331 21.29645509431189 -1.22683777193248 3.965979002972548 21.29645509431189 1.226837771932479 -3.662398832045144 21.29328505571872 1.226837771932479 -3.614033389375331 21.29645509431189 -1.22683777193248 -3.662398832045144 21.29328505571872 -1.22683777193248 -3.614033389375331 21.29645509431189 1.226837771932479 -3.709936728581442 21.28382918017844 1.226837771932479 -3.709936728581442 21.28382918017844 -1.22683777193248 -3.755833692394508 21.2682492603432 1.226837771932479 -3.755833692394508 21.2682492603432 -1.22683777193248 -3.799304413708416 21.24681187296095 1.226837771932479 -3.799304413708416 21.24681187296095 -1.22683777193248 -3.83960509642917 21.21988381767338 1.226837771932479 -3.83960509642917 21.21988381767338 -1.22683777193248 -3.876046184701952 21.18792584097232 1.226837771932479 -3.876046184701952 21.18792584097232 -1.22683777193248 -3.908004161403004 21.15148475269955 -1.22683777193248 -3.908004161403004 21.15148475269955 1.226837771932479 -3.934932216690577 21.11118406997879 -1.22683777193248 -3.934932216690577 21.11118406997879 1.226837771932479 -3.956369604072812 21.06771334866487 -1.22683777193248 -3.956369604072812 21.06771334866487 1.226837771932479 -3.971949523908057 21.02181638485182 -1.22683777193248 -3.971949523908057 21.02181638485182 1.226837771932479 -3.981405399448354 20.97427848831552 -1.22683777193248 -3.981405399448354 20.97427848831552 1.226837771932479 -3.984575438041523 20.9259130456457 -1.22683777193248 -3.984575438041523 20.9259130456457 1.226837771932479 -3.984575438041523 20.9259130456457 1.226837771932479 -3.984575438041523 14.41218903264742 -1.22683777193248 -3.984575438041523 14.41218903264742 1.226837771932479 -3.984575438041523 20.9259130456457 -1.22683777193248 -3.98367628281653 14.40293559688007 1.22683777193248 -3.979887768403605 14.36394702872245 -1.22683777193248 -3.979887768403605 14.36394702872245 1.226837771932479 -3.984575438041523 14.41218903264742 -1.22683777193248 -3.984575438041523 14.41218903264742 1.226837771932479 -3.968943357351909 14.31672960549691 -1.22683777193248 -3.968943357351909 14.31672960549691 1.226837771932479 -3.951929466793871 14.2713446661733 -1.22683777193248 -3.951929466793871 14.2713446661733 1.226837771932479 -3.929137209114053 14.22856875964652 -1.22683777193248 -3.929137209114053 14.22856875964652 1.226837771932479 -3.900956566160614 14.18913379353699 -1.22683777193248 -3.900956566160614 14.18913379353699 1.226837771932479 -3.867869716547619 14.15371451104827 -1.22683777193248 -3.867869716547619 14.15371451104827 1.226837771932479 -3.83044278544533 14.1229169459238 1.226837771932479 -3.83044278544533 14.1229169459238 -1.22683777193248 -3.78931615802163 14.0972680530416 1.226837771932479 -3.78931615802163 14.0972680530416 -1.22683777193248 -3.745193522274203 14.0772066920701 1.226837771932479 -3.745193522274203 14.0772066920701 -1.22683777193248 -3.698829828733795 14.06307611845755 1.226837771932479 -3.698829828733795 14.06307611845755 -1.22683777193248 -3.651018373051289 14.0551181102362 1.226837771932479 -3.651018373051289 14.0551181102362 -1.22683777193248 3.965979002972562 14.0551181102362 -1.22683777193248 0 14.0551181102362 -0.9618994062348557 -3.651018373051289 14.0551181102362 -1.22683777193248 0.248957885806392 14.0551181102362 -0.9291234787743667 0.4809497031174237 14.0551181102362 -0.8330293216845524 3.965979002972562 14.0551181102362 1.226837771932479 0.6801655929679815 14.0551181102362 -0.6801655929679796 0.8330293216845495 14.0551181102362 -0.4809497031174269 0.9150031055983023 14.0551181102362 -0.2830474822338055 0.929123478774365 14.0551181102362 -0.2489578858063867 0.9618994062348565 14.0551181102362 -2.220446049250313e-016 0.929123478774365 14.0551181102362 0.2489578858063872 0.8330293216845495 14.0551181102362 0.4809497031174272 0.6801655929679815 14.0551181102362 0.6801655929679789 0.4809497031174237 14.0551181102362 0.8330293216845512 0.2489578858063849 14.0551181102362 0.9291234787743654 0 14.0551181102362 0.9618994062348538 -0.4809497031174248 14.0551181102362 -0.8330293216845524 -3.651018373051289 14.0551181102362 1.226837771932479 -0.2489578858063836 14.0551181102362 -0.9291234787743667 -0.6801655929679813 14.0551181102362 -0.6801655929679796 -0.8330293216845492 14.0551181102362 -0.4809497031174278 -0.9291234787743649 14.0551181102362 -0.2489578858063871 -0.9618994062348564 14.0551181102362 -4.440892098500626e-016 -0.9291234787743649 14.0551181102362 0.2489578858063863 -0.9150031055983023 14.0551181102362 0.2830474822338065 -0.8330293216845492 14.0551181102362 0.4809497031174264 -0.6801655929679813 14.0551181102362 0.6801655929679789 -0.4809497031174248 14.0551181102362 0.8330293216845508 -0.2489578858063836 14.0551181102362 0.929123478774365 4.01434444564238 14.05828814882938 1.226837771932479 3.965979002972562 14.0551181102362 -1.22683777193248 4.01434444564238 14.05828814882938 -1.22683777193248 3.965979002972562 14.0551181102362 1.226837771932479 4.061882342178663 14.06774402436966 1.226837771932479 4.061882342178663 14.06774402436966 -1.22683777193248 4.107779305991727 14.0833239442049 1.226837771932479 4.107779305991727 14.0833239442049 -1.22683777193248 4.15125002730565 14.10476133158717 1.226837771932479 4.15125002730565 14.10476133158717 -1.22683777193248 4.191550710026419 14.13168938687472 1.226837771932479 4.191550710026419 14.13168938687472 -1.22683777193248 4.22799179829916 14.16364736357579 1.226837771932479 4.22799179829916 14.16364736357579 -1.22683777193248 4.259949775000239 14.20008845184858 -1.22683777193248 4.259949775000239 14.20008845184858 1.226837771932479 4.28687783028781 14.24038913456934 -1.22683777193248 4.28687783028781 14.24038913456934 1.226837771932479 4.308315217670045 14.28385985588327 -1.22683777193248 4.308315217670045 14.28385985588327 1.226837771932479 + + + + + + + + + + 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 4.300417074680833e-018 -5.915144048212544e-017 1 4.300417074680833e-018 -5.915144048212544e-017 1 4.300417074680833e-018 -5.915144048212544e-017 1 4.300417074680833e-018 -5.915144048212544e-017 1 4.300417074680833e-018 -5.915144048212544e-017 1 4.300417074680833e-018 -5.915144048212544e-017 1 4.300417074680833e-018 -5.915144048212544e-017 1 4.300417074680833e-018 -5.915144048212544e-017 1 4.300417074680833e-018 -5.915144048212544e-017 1 4.300417074680833e-018 -5.915144048212544e-017 1 4.300417074680833e-018 -5.915144048212544e-017 1 4.300417074680833e-018 -5.915144048212544e-017 1 4.300417074680833e-018 -5.915144048212544e-017 1 4.300417074680833e-018 -5.915144048212544e-017 1 4.300417074680833e-018 -5.915144048212544e-017 1 4.300417074680833e-018 -5.915144048212544e-017 1 4.300417074680833e-018 -5.915144048212544e-017 1 4.300417074680833e-018 -5.915144048212544e-017 1 4.300417074680833e-018 -5.915144048212544e-017 1 4.300417074680833e-018 -5.915144048212544e-017 1 4.300417074680833e-018 -5.915144048212544e-017 1 4.300417074680833e-018 -5.915144048212544e-017 1 4.300417074680833e-018 -5.915144048212544e-017 1 4.300417074680833e-018 -5.915144048212544e-017 1 4.300417074680833e-018 -5.915144048212544e-017 1 4.300417074680833e-018 -5.915144048212544e-017 1 4.300417074680833e-018 -5.915144048212544e-017 1 4.300417074680833e-018 -5.915144048212544e-017 1 4.300417074680833e-018 -5.915144048212544e-017 1 4.300417074680833e-018 -5.915144048212544e-017 1 4.300417074680833e-018 -5.915144048212544e-017 1 4.300417074680833e-018 -5.915144048212544e-017 1 4.300417074680833e-018 -5.915144048212544e-017 1 4.300417074680833e-018 -5.915144048212544e-017 1 4.300417074680833e-018 -5.915144048212544e-017 1 4.300417074680833e-018 -5.915144048212544e-017 1 4.300417074680833e-018 -5.915144048212544e-017 1 4.300417074680833e-018 -5.915144048212544e-017 1 4.300417074680833e-018 -5.915144048212544e-017 1 4.300417074680833e-018 -5.915144048212544e-017 1 4.300417074680833e-018 -5.915144048212544e-017 1 4.300417074680833e-018 -5.915144048212544e-017 1 4.300417074680833e-018 -5.915144048212544e-017 1 4.300417074680833e-018 -5.915144048212544e-017 1 4.300417074680833e-018 -5.915144048212544e-017 1 4.300417074680833e-018 -5.915144048212544e-017 1 4.300417074680833e-018 -5.915144048212544e-017 1 4.300417074680833e-018 -5.915144048212544e-017 1 4.300417074680833e-018 -5.915144048212544e-017 1 4.300417074680833e-018 -5.915144048212544e-017 1 4.300417074680833e-018 -5.915144048212544e-017 1 4.300417074680833e-018 -5.915144048212544e-017 1 0.9978589232386272 -0.0654031292297835 0 0.9914448613738149 -0.1305261922200165 0 0.9914448613738149 -0.1305261922200165 0 0.9978589232386272 -0.0654031292297835 0 3.707875111323739e-021 6.37041699851231e-017 -1 3.707875111323739e-021 6.37041699851231e-017 -1 3.707875111323739e-021 6.37041699851231e-017 -1 3.707875111323739e-021 6.37041699851231e-017 -1 3.707875111323739e-021 6.37041699851231e-017 -1 3.707875111323739e-021 6.37041699851231e-017 -1 3.707875111323739e-021 6.37041699851231e-017 -1 3.707875111323739e-021 6.37041699851231e-017 -1 3.707875111323739e-021 6.37041699851231e-017 -1 3.707875111323739e-021 6.37041699851231e-017 -1 3.707875111323739e-021 6.37041699851231e-017 -1 3.707875111323739e-021 6.37041699851231e-017 -1 3.707875111323739e-021 6.37041699851231e-017 -1 3.707875111323739e-021 6.37041699851231e-017 -1 3.707875111323739e-021 6.37041699851231e-017 -1 3.707875111323739e-021 6.37041699851231e-017 -1 3.707875111323739e-021 6.37041699851231e-017 -1 3.707875111323739e-021 6.37041699851231e-017 -1 3.707875111323739e-021 6.37041699851231e-017 -1 3.707875111323739e-021 6.37041699851231e-017 -1 3.707875111323739e-021 6.37041699851231e-017 -1 3.707875111323739e-021 6.37041699851231e-017 -1 3.707875111323739e-021 6.37041699851231e-017 -1 3.707875111323739e-021 6.37041699851231e-017 -1 3.707875111323739e-021 6.37041699851231e-017 -1 3.707875111323739e-021 6.37041699851231e-017 -1 3.707875111323739e-021 6.37041699851231e-017 -1 3.707875111323739e-021 6.37041699851231e-017 -1 3.707875111323739e-021 6.37041699851231e-017 -1 3.707875111323739e-021 6.37041699851231e-017 -1 3.707875111323739e-021 6.37041699851231e-017 -1 3.707875111323739e-021 6.37041699851231e-017 -1 3.707875111323739e-021 6.37041699851231e-017 -1 3.707875111323739e-021 6.37041699851231e-017 -1 3.707875111323739e-021 6.37041699851231e-017 -1 3.707875111323739e-021 6.37041699851231e-017 -1 3.707875111323739e-021 6.37041699851231e-017 -1 3.707875111323739e-021 6.37041699851231e-017 -1 3.707875111323739e-021 6.37041699851231e-017 -1 3.707875111323739e-021 6.37041699851231e-017 -1 3.707875111323739e-021 6.37041699851231e-017 -1 3.707875111323739e-021 6.37041699851231e-017 -1 3.707875111323739e-021 6.37041699851231e-017 -1 3.707875111323739e-021 6.37041699851231e-017 -1 3.707875111323739e-021 6.37041699851231e-017 -1 3.707875111323739e-021 6.37041699851231e-017 -1 3.707875111323739e-021 6.37041699851231e-017 -1 3.707875111323739e-021 6.37041699851231e-017 -1 3.707875111323739e-021 6.37041699851231e-017 -1 3.707875111323739e-021 6.37041699851231e-017 -1 3.707875111323739e-021 6.37041699851231e-017 -1 0.9914448613738179 0.1305261922199955 0 0.9978589232386074 0.06540312923008501 -0 0.9978589232386074 0.06540312923008501 -0 0.9914448613738179 0.1305261922199955 0 0.9659258262890084 -0.2588190451027445 0 0.9659258262890084 -0.2588190451027445 0 0.965925826289053 0.258819045102578 0 0.965925826289053 0.258819045102578 0 0.9238795325112421 0.3826834323651973 0 0.9238795325112421 0.3826834323651973 0 0.8660254037844077 0.5000000000000536 0 0.8660254037844077 0.5000000000000536 0 0.7933533402912777 0.6087614290086653 0 0.7933533402912777 0.6087614290086653 0 0.7071067811865438 0.7071067811865511 0 0.7071067811865438 0.7071067811865511 0 0.6087614290086229 0.7933533402913102 0 0.6087614290086229 0.7933533402913102 0 0.499999999999983 0.8660254037844486 0 0.499999999999983 0.8660254037844486 0 0.3826834323651025 0.9238795325112816 0 0.3826834323651025 0.9238795325112816 0 0.2588190451025265 0.9659258262890667 0 0.2588190451025265 0.9659258262890667 0 0.1305261922200078 0.9914448613738162 0 0.1305261922200078 0.9914448613738162 0 0.06540312923007782 0.9978589232386078 -0 0.06540312923007782 0.9978589232386078 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0.130526192220009 0.9914448613738159 0 -0.06540312923008382 0.9978589232386074 -0 -0.130526192220009 0.9914448613738159 0 -0.06540312923008382 0.9978589232386074 -0 -0.2588190451024735 0.965925826289081 0 -0.2588190451024735 0.965925826289081 0 -0.3826834323651778 0.9238795325112503 0 -0.3826834323651778 0.9238795325112503 0 -0.5000000000001039 0.8660254037843786 0 -0.5000000000001039 0.8660254037843786 0 -0.6087614290086315 0.7933533402913034 0 -0.6087614290086315 0.7933533402913034 0 -0.7071067811865384 0.7071067811865567 0 -0.7071067811865384 0.7071067811865567 0 -0.7933533402913119 0.6087614290086207 0 -0.7933533402913119 0.6087614290086207 0 -0.866025403784476 0.4999999999999354 0 -0.866025403784476 0.4999999999999354 0 -0.9238795325112743 0.3826834323651198 0 -0.9238795325112743 0.3826834323651198 0 -0.9659258262890202 0.2588190451027001 0 -0.9659258262890202 0.2588190451027001 0 -0.991444861373799 0.130526192220138 0 -0.991444861373799 0.130526192220138 0 -0.9978589232386074 0.06540312923008501 0 -0.9978589232386074 0.06540312923008501 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.9953121781612281 -0.09671436296616837 5.858798327943037e-016 -0.9868557164067743 -0.1616038211035629 2.935684690240544e-016 -0.9868557164067743 -0.1616038211035624 2.935684690240566e-016 -0.9953121781612281 -0.09671436296616837 5.858798327943037e-016 -0.9953121781612281 -0.09671436296616837 5.858798327943037e-016 -0.9573194975320817 -0.2890317969444237 0 -0.9573194975320817 -0.2890317969444237 0 -0.9114032766354122 -0.4115143586051823 0 -0.9114032766354122 -0.4115143586051823 0 -0.8498926929868138 -0.5269557954967583 0 -0.8498926929868138 -0.5269557954967583 0 -0.7738402097265843 -0.6333808726274547 0 -0.7738402097265843 -0.6333808726274547 0 -0.6845471059288371 -0.7289686274212721 0 -0.6845471059288371 -0.7289686274212721 0 -0.5835412113562485 -0.8120835268917123 0 -0.5835412113562485 -0.8120835268917123 0 -0.4725507648689741 -0.8813034520650351 0 -0.4725507648689741 -0.8813034520650351 0 -0.3534748437792569 -0.9354440308298675 0 -0.3534748437792569 -0.9354440308298675 0 -0.2283508701109189 -0.9735789028730986 0 -0.2283508701109189 -0.9735789028730986 0 -0.1641868465691506 -0.9864292571764476 0 -0.1641868465691506 -0.9864292571764476 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0.1305261922201096 -0.9914448613738028 0 0.06540312923036916 -0.9978589232385887 0 0.1305261922201096 -0.9914448613738028 0 0.06540312923036916 -0.9978589232385887 0 0.2588190451024391 -0.9659258262890902 0 0.2588190451024391 -0.9659258262890902 0 0.3826834323653019 -0.923879532511199 0 0.3826834323653019 -0.923879532511199 0 0.4999999999999819 -0.8660254037844491 0 0.4999999999999819 -0.8660254037844491 0 0.6087614290087305 -0.7933533402912275 0 0.6087614290087305 -0.7933533402912275 0 0.7071067811867735 -0.7071067811863218 0 0.7071067811867735 -0.7071067811863218 0 0.7933533402912565 -0.6087614290086927 0 0.7933533402912565 -0.6087614290086927 0 0.8660254037844938 -0.4999999999999046 0 0.8660254037844938 -0.4999999999999046 0 0.9238795325112926 -0.3826834323650759 0 0.9238795325112926 -0.3826834323650759 0 + + + + + + + + + + + + + + +

0 1 2 1 0 3 4 5 6 5 4 7 7 4 8 7 8 9 9 8 10 9 10 11 11 10 12 11 12 13 13 12 14 13 14 15 15 14 16 15 16 17 17 16 18 17 18 19 19 18 20 19 20 21 21 20 22 21 22 23 23 22 24 23 24 25 25 24 26 25 26 27 27 26 28 27 28 29 29 28 30 29 30 31 31 30 32 32 30 33 32 33 34 34 33 35 34 35 36 34 36 37 37 36 38 38 36 39 38 39 40 40 39 41 40 41 42 42 41 43 42 43 44 42 44 45 45 44 46 46 44 47 46 47 48 48 47 49 48 49 50 48 50 51 51 50 52 51 52 53 53 52 54 54 52 55 56 57 58 57 56 59 60 61 62 61 60 63 63 60 64 63 64 65 65 64 66 65 66 67 67 66 68 67 68 69 69 68 70 69 70 71 71 70 72 71 72 73 73 72 74 73 74 75 75 74 76 75 76 77 77 76 78 77 78 79 79 78 80 79 80 81 81 80 82 81 82 83 83 82 84 83 84 85 85 84 86 85 86 87 85 87 88 88 87 89 88 89 90 90 89 91 90 91 92 92 91 93 92 93 94 94 93 95 94 95 96 96 95 97 96 97 98 98 97 99 99 97 100 99 100 101 99 101 102 102 101 103 102 103 104 104 103 105 104 105 106 106 105 107 106 107 108 108 107 109 108 109 110 111 112 113 112 111 114 58 115 116 115 58 57 117 114 111 114 117 118 119 118 117 118 119 120 121 120 119 120 121 122 123 122 121 122 123 124 125 124 123 124 125 126 127 125 128 125 127 126 129 128 130 128 129 127 131 130 132 130 131 129 133 132 134 132 133 131 135 134 136 134 135 133 137 136 138 136 137 135 139 140 141 140 139 142 143 144 145 144 143 146 147 145 148 145 147 143 149 148 150 148 149 147 151 150 152 150 151 149 153 152 154 152 153 151 155 154 156 154 155 153 155 157 158 157 155 156 158 159 160 159 158 157 160 161 162 161 160 159 162 163 164 163 162 161 164 165 166 165 164 163 166 167 168 167 166 165 169 170 171 170 169 172 173 174 175 174 173 176 176 173 177 175 178 179 178 175 174 179 180 181 180 179 178 181 182 183 182 181 180 183 184 185 184 183 182 185 186 187 186 185 184 188 186 189 186 188 187 190 189 191 189 190 188 192 191 193 191 192 190 194 193 195 193 194 192 196 195 197 195 196 194 198 199 200 199 198 201 201 198 202 202 198 203 202 203 204 204 203 205 205 203 206 206 203 207 207 203 208 208 203 209 209 203 210 210 203 211 211 203 212 212 203 213 213 203 214 200 215 216 215 200 217 217 200 199 216 215 218 216 218 219 216 219 220 216 220 221 216 221 222 216 222 223 216 223 224 216 224 225 216 225 226 216 226 227 216 227 214 216 214 203 228 229 230 229 228 231 232 230 233 230 232 228 234 233 235 233 234 232 236 235 237 235 236 234 238 237 239 237 238 236 240 239 241 239 240 238 242 240 241 240 242 243 244 243 242 243 244 245 246 245 244 245 246 247 116 247 246 247 116 115

+
+
+
+ + + + -1.925361975877098 8.464566929133859 0.6336272275916833 -1.979999782201047 0 0.5033079051575167 -1.925361975877098 0 0.6336272275916833 -1.979999782201047 8.464566929133859 0.5033079051575167 -1.783362903228357 8.464566929133859 0.9723162083341679 -1.925361975877098 0 0.6336272275916833 -1.783362903228357 0 0.9723162083341679 -1.925361975877098 8.464566929133859 0.6336272275916833 -1.925361975877098 8.464566929133859 0.6336272275916833 -1.391790358907926 9.015748031496067 0.480539228921264 -1.979999782201047 8.464566929133859 0.5033079051575167 -2.047068959729108 0 -8.311407118100078e-016 -2.047068959729108 8.464566929133859 -8.311407118100078e-016 0.4307008235655168 0 -1.878370673898857 -0.5881811385261369 0 -1.878370673898857 -0.07874015748031514 0 -1.944632416668323 0.9054242436440817 0 -1.684101073857492 -1.062904558604711 0 -1.684101073857495 -1.470558801155224 0 -1.375062768741364 1.313078486194594 0 -1.375062768741363 -1.783362903228357 0 -0.9723162083341714 1.625882588267746 0 -0.9723162083341397 -1.979999782201047 0 -0.5033079051575021 1.76788166091646 0 -0.6336272275916925 1.822519467240419 0 -0.5033079051575071 1.889588644768482 0 8.532063944244329e-016 -2.047068959729108 0 -8.311407118100078e-016 -1.979999782201047 0 0.5033079051575167 1.822519467240419 0 0.5033079051575041 1.625882588267727 0 0.9723162083341703 -1.925361975877098 0 0.6336272275916833 -1.783362903228357 0 0.9723162083341679 -1.470558801155224 0 1.375062768741361 1.313078486194594 0 1.375062768741363 -1.062904558604711 0 1.684101073857492 0.9054242436440817 0 1.684101073857492 -0.5881811385261369 0 1.878370673898856 0.4307008235655077 0 1.878370673898856 -0.07874015748031514 0 1.944632416668323 -1.470558801155224 8.464566929133859 1.375062768741361 -1.470558801155224 0 1.375062768741361 -1.783362903228357 8.464566929133859 0.9723162083341679 -1.28381629328986 9.015748031496067 0.7412116825209396 -1.431911013788287 9.015748031496067 0.3836793997778125 -1.482423365041874 9.015748031496067 0 -2.047068959729108 8.464566929133859 -8.311407118100078e-016 -1.979999782201047 0 -0.5033079051575021 -1.979999782201047 8.464566929133859 -0.5033079051575021 0.9054242436440817 0 1.684101073857492 0.4307008235655077 8.464566929133859 1.878370673898856 0.4307008235655077 0 1.878370673898856 0.9054242436440817 8.464566929133859 1.684101073857492 -0.07874015748031514 8.464566929133859 1.944632416668323 -0.07874015748031514 0 1.944632416668323 -0.5881811385261369 8.464566929133859 1.878370673898856 -0.5881811385261369 0 1.878370673898856 -1.062904558604711 8.464566929133859 1.684101073857492 -1.062904558604711 0 1.684101073857492 -1.783362903228357 0 -0.9723162083341714 -1.783362903228357 8.464566929133859 -0.9723162083341714 -1.470558801155224 0 -1.375062768741364 -1.470558801155224 8.464566929133859 -1.375062768741364 -1.062904558604711 8.464566929133859 -1.684101073857495 -1.062904558604711 0 -1.684101073857495 -0.5881811385261369 8.464566929133859 -1.878370673898857 -0.5881811385261369 0 -1.878370673898857 -0.07874015748031514 8.464566929133859 -1.944632416668323 -0.07874015748031514 0 -1.944632416668323 0.4307008235655168 8.464566929133859 -1.878370673898857 0.4307008235655168 0 -1.878370673898857 0.9054242436440817 8.464566929133859 -1.684101073857492 0.9054242436440817 0 -1.684101073857492 1.313078486194594 8.464566929133859 -1.375062768741363 1.313078486194594 0 -1.375062768741363 1.625882588267746 0 -0.9723162083341397 1.625882588267746 8.464566929133859 -0.9723162083341397 1.76788166091646 0 -0.6336272275916925 1.76788166091646 8.464566929133859 -0.6336272275916925 1.76788166091646 8.464566929133859 -0.6336272275916925 1.822519467240419 0 -0.5033079051575071 1.76788166091646 0 -0.6336272275916925 1.822519467240419 8.464566929133859 -0.5033079051575071 1.889588644768482 0 8.532063944244329e-016 1.889588644768482 8.464566929133859 8.532063944244329e-016 1.822519467240419 0 0.5033079051575041 1.822519467240419 8.464566929133859 0.5033079051575041 1.625882588267727 0 0.9723162083341703 1.625882588267727 8.464566929133859 0.9723162083341703 1.313078486194594 0 1.375062768741363 1.313078486194594 8.464566929133859 1.375062768741363 -1.470558801155224 8.464566929133859 1.375062768741361 -1.048231614010476 9.015748031496067 1.048231614010499 -1.783362903228357 8.464566929133859 0.9723162083341679 -1.28381629328986 9.015748031496067 0.7412116825209396 -0.3836793997777976 9.015748031496067 -1.431911013788291 0.383679399777805 9.015748031496067 -1.431911013788291 0 9.015748031496067 -1.482423365041872 -0.7412116825209407 9.015748031496067 -1.283816293289871 0.7412116825209336 9.015748031496067 -1.283816293289871 1.048231614010483 9.015748031496067 -1.048231614010494 -1.048231614010483 9.015748031496067 -1.048231614010495 0 9.015748031496067 -0.9618994062348557 -0.2489578858063836 9.015748031496067 -0.9291234787743667 -1.283816293289867 9.015748031496067 -0.7412116825209403 -0.4809497031174248 9.015748031496067 -0.8330293216845524 -0.6801655929679813 9.015748031496067 -0.6801655929679796 -1.431911013788287 9.015748031496067 -0.3836793997778019 -0.8330293216845492 9.015748031496067 -0.4809497031174278 -0.9291234787743649 9.015748031496067 -0.2489578858063871 -1.482423365041874 9.015748031496067 0 -0.9618994062348564 9.015748031496067 -4.440892098500626e-016 -0.9291234787743649 9.015748031496067 0.2489578858063863 -1.431911013788287 9.015748031496067 0.3836793997778125 -0.9150031055983023 9.015748031496067 0.2830474822338065 -0.8330293216845492 9.015748031496067 0.4809497031174264 -1.391790358907926 9.015748031496067 0.480539228921264 -1.28381629328986 9.015748031496067 0.7412116825209396 -0.6801655929679813 9.015748031496067 0.6801655929679789 -0.4809497031174248 9.015748031496067 0.8330293216845508 -1.048231614010476 9.015748031496067 1.048231614010499 -0.2489578858063836 9.015748031496067 0.929123478774365 0 9.015748031496067 0.9618994062348538 1.048231614010483 9.015748031496067 1.048231614010493 0.7412116825209336 9.015748031496067 1.283816293289871 -0.7412116825209407 9.015748031496067 1.28381629328987 -0.3836793997778047 9.015748031496067 1.43191101378829 0.3836793997777979 9.015748031496067 1.431911013788291 0 9.015748031496067 1.482423365041872 0.248957885806392 9.015748031496067 -0.9291234787743667 1.283816293289873 9.015748031496067 -0.7412116825209199 0.4809497031174237 9.015748031496067 -0.8330293216845524 0.6801655929679815 9.015748031496067 -0.6801655929679796 1.391790358907921 9.015748031496067 -0.4805392289212703 0.8330293216845495 9.015748031496067 -0.4809497031174269 0.9150031055983023 9.015748031496067 -0.2830474822338055 1.431911013788288 9.015748031496067 -0.383679399777801 1.482423365041877 9.015748031496067 1.554312234475219e-015 0.929123478774365 9.015748031496067 -0.2489578858063867 0.9618994062348565 9.015748031496067 -2.220446049250313e-016 0.929123478774365 9.015748031496067 0.2489578858063872 1.431911013788288 9.015748031496067 0.3836793997778045 0.8330293216845495 9.015748031496067 0.4809497031174272 1.283816293289859 9.015748031496067 0.7412116825209434 0.6801655929679815 9.015748031496067 0.6801655929679789 0.4809497031174237 9.015748031496067 0.8330293216845512 0.2489578858063849 9.015748031496067 0.9291234787743654 -1.482423365041874 9.015748031496067 0 -1.431911013788287 9.015748031496067 -0.3836793997778019 -2.047068959729108 8.464566929133859 -8.311407118100078e-016 -1.979999782201047 8.464566929133859 -0.5033079051575021 0.9054242436440817 8.464566929133859 1.684101073857492 0.3836793997777979 9.015748031496067 1.431911013788291 0.4307008235655077 8.464566929133859 1.878370673898856 0 9.015748031496067 1.482423365041872 -0.07874015748031514 8.464566929133859 1.944632416668323 -0.5881811385261369 8.464566929133859 1.878370673898856 -0.3836793997778047 9.015748031496067 1.43191101378829 -1.062904558604711 8.464566929133859 1.684101073857492 -0.7412116825209407 9.015748031496067 1.28381629328987 -1.283816293289867 9.015748031496067 -0.7412116825209403 -1.783362903228357 8.464566929133859 -0.9723162083341714 -1.048231614010483 9.015748031496067 -1.048231614010495 -1.470558801155224 8.464566929133859 -1.375062768741364 -0.7412116825209407 9.015748031496067 -1.283816293289871 -1.062904558604711 8.464566929133859 -1.684101073857495 -0.3836793997777976 9.015748031496067 -1.431911013788291 -0.5881811385261369 8.464566929133859 -1.878370673898857 0 9.015748031496067 -1.482423365041872 -0.07874015748031514 8.464566929133859 -1.944632416668323 0.4307008235655168 8.464566929133859 -1.878370673898857 0.9054242436440817 8.464566929133859 -1.684101073857492 0.383679399777805 9.015748031496067 -1.431911013788291 1.313078486194594 8.464566929133859 -1.375062768741363 0.7412116825209336 9.015748031496067 -1.283816293289871 1.048231614010483 9.015748031496067 -1.048231614010494 1.625882588267746 8.464566929133859 -0.9723162083341397 1.283816293289873 9.015748031496067 -0.7412116825209199 1.76788166091646 8.464566929133859 -0.6336272275916925 1.391790358907921 9.015748031496067 -0.4805392289212703 1.822519467240419 8.464566929133859 -0.5033079051575071 1.431911013788288 9.015748031496067 -0.383679399777801 1.889588644768482 8.464566929133859 8.532063944244329e-016 1.482423365041877 9.015748031496067 1.554312234475219e-015 1.822519467240419 8.464566929133859 0.5033079051575041 1.283816293289859 9.015748031496067 0.7412116825209434 1.625882588267727 8.464566929133859 0.9723162083341703 1.048231614010483 9.015748031496067 1.048231614010493 1.313078486194594 8.464566929133859 1.375062768741363 0.7412116825209336 9.015748031496067 1.283816293289871 1.431911013788288 9.015748031496067 0.3836793997778045 + + + + + + + + + + -0.9222252502952645 0 0.3866530585910796 -0.9651611001167182 0 0.2616563601777837 -0.9222252502952645 0 0.3866530585910796 -0.9651611001167182 0 0.2616563601777837 -0.8634744487151208 0 0.5043925816426311 -0.9222252502952602 0 0.38665305859109 -0.8634744487151208 0 0.5043925816426311 -0.9222252502952602 0 0.38665305859109 -0.6524332885953611 0.7068943383828954 0.273187112241502 -0.6528620341633181 0.7074901913012489 0.270608191968863 -0.67735905786961 0.7129458654008288 0.1813639978878319 -0.9999999999999999 0 -2.103461149605589e-015 -0.9999999999999999 0 -2.103461149605589e-015 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.7029585082110135 0 0.7112308596607337 -0.7029585082110135 0 0.7112308596607337 -0.6527801367795563 0.7063812595962551 0.2736852373024022 -0.6529891505322774 0.7070717753090481 0.2713939458581302 -0.6768349913849168 0.712879415735472 0.1835683334827433 -0.6958862047238174 0.7122326580518353 0.0920164706968193 -0.695516757455536 0.7125071441044114 0.09268230520823582 -0.9651611001167185 0 -0.2616563601777831 -0.9651611001167185 0 -0.2616563601777831 0.495618406573377 0 0.8685403819429853 0.2560060840294308 0 0.9666751703338181 0.2560060840294308 0 0.9666751703338181 0.495618406573377 0 0.8685403819429853 -1.514579807304056e-016 0 1 -1.514579807304056e-016 0 1 -0.2560060840294315 0 0.9666751703338179 -0.2560060840294315 0 0.9666751703338179 -0.4956184065733781 0 0.8685403819429848 -0.4956184065733781 0 0.8685403819429848 -0.8634744487151249 0 -0.504392581642624 -0.8634744487151249 0 -0.504392581642624 -0.7029585082110134 0 -0.7112308596607339 -0.7029585082110134 0 -0.7112308596607339 -0.4956184065733762 0 -0.8685403819429858 -0.4956184065733762 0 -0.8685403819429858 -0.2560060840294291 0 -0.9666751703338185 -0.2560060840294291 0 -0.9666751703338185 -1.274028896732235e-015 0 -1 -1.274028896732235e-015 0 -1 0.2560060840294339 0 -0.9666751703338172 0.2560060840294339 0 -0.9666751703338172 0.4956184065733802 0 -0.8685403819429834 0.4956184065733802 0 -0.8685403819429834 0.7029585082110155 0 -0.7112308596607319 0.7029585082110155 0 -0.7112308596607319 0.8634744487151302 0 -0.5043925816426149 0.8634744487151302 0 -0.5043925816426149 0.9222252502952714 -0 -0.3866530585910631 0.9222252502952714 -0 -0.3866530585910631 0.9222252502952569 -0 -0.3866530585910977 0.965161100116715 0 -0.2616563601777958 0.9222252502952569 -0 -0.3866530585910977 0.965161100116715 0 -0.2616563601777958 1 0 6.149949971304479e-016 1 0 6.149949971304479e-016 0.9651611001167172 0 0.2616563601777878 0.9651611001167172 0 0.2616563601777878 0.8634744487151234 0 0.5043925816426268 0.8634744487151234 0 0.5043925816426268 0.7029585082110134 0 0.711230859660734 0.7029585082110134 0 0.711230859660734 -0.5111151250827924 0.6925225601586134 0.5090911829750749 -0.5050289461943278 0.6931090486308255 0.514339975319748 -0.5675281820828995 0.6964452976937111 0.4391761717830301 -0.5682456857918998 0.6978355545674408 0.4360302505107254 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0.6955882614958354 0.712580394876589 -0.09157593191841378 -0.6766289135106639 0.7130312722323986 -0.1837381784497329 -0.6958091149009213 0.7122594831487282 -0.0923910400715513 -0.6777560707386288 0.7125760385761778 -0.1813342158116234 0.3874392962523859 0.6139952358434436 0.6876777167256549 0.2075839823645708 0.6269507264292457 0.750893918536771 0.1939763816432534 0.627222802624507 0.7542975004813748 0.007500423028916298 0.6423091314933227 0.7664089791062477 -0.006364883797432481 0.643074287221015 0.765777349736481 -0.198696382320986 0.6601823891358526 0.7243472652860851 -0.1865816143881681 0.6597346211176554 0.7279680836898337 -0.3702919640699069 0.677179785642846 0.6358548570719262 -0.3610591590743343 0.6773625698055464 0.6409494774745985 -0.6114995403572023 0.7053794405208838 -0.3584803439986293 -0.6147585696804279 0.7047003541881854 -0.3542164759176519 -0.5050289461943274 0.6931090486308248 -0.5143399753197493 -0.5111151250827918 0.6925225601586135 -0.5090911829750756 -0.361059159074331 0.6773625698055477 -0.6409494774745993 -0.3702919640699046 0.6771797856428478 -0.6358548570719258 -0.1865816143881661 0.6597346211176565 -0.7279680836898332 -0.1986963823209847 0.6601823891358538 -0.7243472652860844 0.007500423028915253 0.6423091314933234 -0.766408979106247 -0.006364883797433302 0.6430742872210152 -0.7657773497364808 0.1939763816432558 0.627222802624508 -0.7542975004813735 0.3874392962523883 0.6139952358434432 -0.6876777167256538 0.2075839823645734 0.6269507264292462 -0.7508939185367698 0.5580019323324017 0.6042452467917472 -0.5687895263125776 0.3986033211660927 0.6145356605359472 -0.6807799308770842 0.5652966163044468 0.6052959759708505 -0.5604074562925074 0.6912189343326179 0.5979673386710613 -0.4057726539612152 0.6947115475231506 0.5989614211938515 -0.3982726222820631 0.7429643216057414 0.5926759069898121 -0.3110293974767079 0.7435748464559432 0.5933664504072079 -0.3082413068509326 0.7753992010303746 0.5950667903426626 -0.2113092380203431 0.7763601836023366 0.595416449130206 -0.2067465052234818 0.8044796808356202 0.5939801394328534 0.0001925667333421602 0.804504178497591 0.5939469242196831 0.0002792667074009 0.7756600181682932 0.5949088051285441 0.2107962281344021 0.6945505841277383 0.5990703724962089 0.3983894763733988 0.6912189343326122 0.5979673386710614 0.405772653961225 0.5652966163044447 0.6052959759708506 0.5604074562925094 0.5580019323323999 0.6042452467917476 0.5687895263125791 0.3986033211660913 0.6145356605359481 0.6807799308770844 0.7766012832166183 0.5951810497776406 0.2065186792808041 + + + + + + + + + + + + + + +

0 1 2 1 0 3 4 5 6 5 4 7 8 9 10 3 11 1 11 3 12 13 14 15 14 13 16 14 16 17 17 16 18 18 16 19 18 19 20 20 19 21 20 21 22 22 21 23 22 23 24 22 24 25 22 25 26 26 25 27 27 25 28 27 28 29 27 29 30 30 29 31 31 29 32 32 29 33 32 33 34 34 33 35 34 35 36 36 35 37 36 37 38 39 6 40 6 39 4 41 42 8 42 9 8 10 9 43 10 44 45 12 46 11 46 12 47 48 49 50 49 48 51 50 52 53 52 50 49 53 54 55 54 53 52 55 56 57 56 55 54 57 39 40 39 57 56 47 58 46 58 47 59 59 60 58 60 59 61 62 60 61 60 62 63 64 63 62 63 64 65 66 65 64 65 66 67 68 67 66 67 68 69 70 69 68 69 70 71 72 71 70 71 72 73 72 74 73 74 72 75 75 76 74 76 75 77 78 79 80 79 78 81 81 82 79 82 81 83 83 84 82 84 83 85 85 86 84 86 85 87 87 88 86 88 87 89 88 51 48 51 88 89 90 91 92 91 93 92 94 95 96 95 94 97 95 97 98 98 97 99 99 97 100 99 100 101 101 100 102 102 100 103 102 103 104 104 103 105 105 103 106 105 106 107 107 106 108 108 106 109 108 109 110 110 109 111 111 109 112 111 112 113 113 112 114 114 112 115 114 115 116 114 116 117 117 116 118 118 116 119 118 119 120 120 119 121 121 119 122 122 119 123 123 119 124 123 124 125 123 125 126 126 125 127 99 128 129 128 99 101 129 128 130 129 130 131 129 131 132 132 131 133 132 133 134 132 134 135 135 134 136 136 134 137 136 137 138 136 138 139 136 139 140 140 139 141 140 141 142 142 141 143 142 143 144 142 144 122 122 144 145 122 145 121 10 43 44 146 147 148 148 147 149 150 151 152 152 153 154 153 155 154 156 157 155 157 158 90 149 159 160 160 161 162 163 164 162 165 166 164 167 168 166 169 168 167 170 169 171 172 170 173 174 175 172 176 177 175 178 179 177 180 181 179 182 183 181 184 185 183 186 187 185 187 188 150 90 158 91 156 158 157 153 156 155 152 151 153 150 188 151 187 186 188 186 185 184 184 183 189 189 183 182 182 181 180 180 179 178 178 177 176 176 175 174 172 173 174 170 171 173 169 167 171 167 166 165 165 164 163 161 163 162 159 161 160 147 159 149

+
+
+
+ + + + -0.9291234787743649 14.0551181102362 0.2489578858063863 -0.9618994062348564 9.015748031496067 -4.440892098500626e-016 -0.9291234787743649 9.015748031496067 0.2489578858063863 -0.9618994062348564 14.0551181102362 -4.440892098500626e-016 -0.9150031055983023 14.0551181102362 0.2830474822338065 -0.9150031055983023 9.015748031496067 0.2830474822338065 -0.9291234787743649 9.015748031496067 -0.2489578858063871 -0.9291234787743649 14.0551181102362 -0.2489578858063871 -0.8330293216845492 14.0551181102362 0.4809497031174264 -0.9150031055983023 9.015748031496067 0.2830474822338065 -0.8330293216845492 9.015748031496067 0.4809497031174264 -0.9150031055983023 14.0551181102362 0.2830474822338065 -0.8330293216845492 9.015748031496067 -0.4809497031174278 -0.8330293216845492 14.0551181102362 -0.4809497031174278 -0.6801655929679813 14.0551181102362 0.6801655929679789 -0.6801655929679813 9.015748031496067 0.6801655929679789 -0.6801655929679813 9.015748031496067 -0.6801655929679796 -0.6801655929679813 14.0551181102362 -0.6801655929679796 -0.4809497031174248 9.015748031496067 0.8330293216845508 -0.4809497031174248 14.0551181102362 0.8330293216845508 -0.4809497031174248 14.0551181102362 -0.8330293216845524 -0.4809497031174248 9.015748031496067 -0.8330293216845524 -0.2489578858063836 9.015748031496067 0.929123478774365 -0.2489578858063836 14.0551181102362 0.929123478774365 -0.2489578858063836 14.0551181102362 -0.9291234787743667 -0.2489578858063836 9.015748031496067 -0.9291234787743667 0 9.015748031496067 0.9618994062348538 0 14.0551181102362 0.9618994062348538 0 14.0551181102362 -0.9618994062348557 0 9.015748031496067 -0.9618994062348557 0.2489578858063849 9.015748031496067 0.9291234787743654 0.2489578858063849 14.0551181102362 0.9291234787743654 0.248957885806392 14.0551181102362 -0.9291234787743667 0.248957885806392 9.015748031496067 -0.9291234787743667 0.4809497031174237 9.015748031496067 0.8330293216845512 0.4809497031174237 14.0551181102362 0.8330293216845512 0.4809497031174237 14.0551181102362 -0.8330293216845524 0.4809497031174237 9.015748031496067 -0.8330293216845524 0.6801655929679815 9.015748031496067 0.6801655929679789 0.6801655929679815 14.0551181102362 0.6801655929679789 0.6801655929679815 14.0551181102362 -0.6801655929679796 0.6801655929679815 9.015748031496067 -0.6801655929679796 0.8330293216845495 14.0551181102362 0.4809497031174272 0.8330293216845495 9.015748031496067 0.4809497031174272 0.8330293216845495 9.015748031496067 -0.4809497031174269 0.8330293216845495 14.0551181102362 -0.4809497031174269 0.929123478774365 14.0551181102362 0.2489578858063872 0.929123478774365 9.015748031496067 0.2489578858063872 0.9150031055983023 9.015748031496067 -0.2830474822338055 0.9150031055983023 14.0551181102362 -0.2830474822338055 0.9618994062348565 14.0551181102362 -2.220446049250313e-016 0.9618994062348565 9.015748031496067 -2.220446049250313e-016 0.9150031055983023 14.0551181102362 -0.2830474822338055 0.929123478774365 9.015748031496067 -0.2489578858063867 0.9150031055983023 9.015748031496067 -0.2830474822338055 0.929123478774365 14.0551181102362 -0.2489578858063867 + + + + + + + + + + -0.9659258262890678 0 0.2588190451025227 -1 0 -4.45555494782346e-017 -0.9659258262890678 0 0.2588190451025227 -1 0 -4.45555494782346e-017 -0.92387953251129 0 0.3826834323650825 -0.92387953251129 0 0.3826834323650825 -0.9659258262890661 0 -0.2588190451025286 -0.9659258262890661 0 -0.2588190451025286 -0.8660254037844406 0 0.4999999999999968 -0.9238795325112839 0 0.3826834323650969 -0.8660254037844406 0 0.4999999999999968 -0.9238795325112839 0 0.3826834323650969 -0.8660254037844409 0 -0.499999999999996 -0.8660254037844409 0 -0.499999999999996 -0.7071067811865484 0 0.7071067811865466 -0.7071067811865484 0 0.7071067811865466 -0.7071067811865488 0 -0.7071067811865462 -0.7071067811865488 0 -0.7071067811865462 -0.499999999999994 -7.493747219374589e-034 0.8660254037844423 -0.499999999999994 -7.493747219374589e-034 0.8660254037844423 -0.4999999999999954 0 -0.8660254037844414 -0.4999999999999954 0 -0.8660254037844414 -0.2588190451025214 -7.493747219374592e-034 0.9659258262890682 -0.2588190451025214 -7.493747219374592e-034 0.9659258262890682 -0.258819045102522 0 -0.965925826289068 -0.258819045102522 0 -0.965925826289068 -1.176266506225392e-015 0 1 -1.176266506225392e-015 0 1 -2.165399704642198e-015 0 -1 -2.165399704642198e-015 0 -1 0.258819045102522 -1.522257965794536e-032 0.9659258262890679 0.258819045102522 -1.522257965794536e-032 0.9659258262890679 0.2588190451025268 0 -0.9659258262890667 0.2588190451025268 0 -0.9659258262890667 0.4999999999999947 -1.522257965794535e-032 0.8660254037844417 0.4999999999999947 -1.522257965794535e-032 0.8660254037844417 0.5000000000000003 0 -0.8660254037844386 0.5000000000000003 0 -0.8660254037844386 0.7071067811865471 0 0.707106781186548 0.7071067811865471 0 0.707106781186548 0.7071067811865486 0 -0.7071067811865466 0.7071067811865486 0 -0.7071067811865466 0.8660254037844407 0 0.4999999999999965 0.8660254037844407 0 0.4999999999999965 0.8660254037844417 0 -0.4999999999999948 0.8660254037844417 0 -0.4999999999999948 0.9659258262890662 0 0.2588190451025288 0.9659258262890662 0 0.2588190451025288 0.9238795325112854 -0 -0.3826834323650936 0.9238795325112854 -0 -0.3826834323650936 1 0 -2.584221869737607e-016 1 0 -2.584221869737607e-016 0.9238795325112835 -0 -0.3826834323650978 0.9659258262890655 0 -0.2588190451025308 0.9238795325112835 -0 -0.3826834323650978 0.9659258262890655 0 -0.2588190451025308 + + + + + + + + + + -0.260279965004374 0.002325056792491714 -0.1669582968795568 -0.00232505679249215 -0.1669582968795568 0.002325056792491714 -0.260279965004374 -0.00232505679249215 -0.260279965004374 -0.001641754694637065 -0.1669582968795568 -0.002325056792491786 -0.1669582968795568 -0.001641754694637065 -0.260279965004374 -0.002325056792491786 -0.260279965004374 0.002325056792492135 -0.1669582968795568 -0.002325056792491726 -0.1669582968795568 0.002325056792492135 -0.260279965004374 -0.002325056792491726 -0.260279965004374 0.002325056792491793 -0.1669582968795568 -0.001641754694637343 -0.1669582968795568 0.002325056792491793 -0.260279965004374 -0.001641754694637343 -0.260279965004374 0.002325056792491992 -0.1669582968795568 -0.002325056792491877 -0.1669582968795568 0.002325056792491992 -0.260279965004374 -0.002325056792491877 -0.260279965004374 0.002325056792492168 -0.1669582968795568 -0.002325056792491643 -0.1669582968795568 0.002325056792492168 -0.260279965004374 -0.002325056792491643 -0.260279965004374 0.002325056792491651 -0.1669582968795568 -0.002325056792492153 -0.1669582968795568 0.002325056792491651 -0.260279965004374 -0.002325056792492153 -0.1669582968795568 0.002325056792491736 -0.260279965004374 -0.002325056792492181 -0.1669582968795568 -0.002325056792492181 -0.260279965004374 0.002325056792491736 -0.260279965004374 -0.002325056792491796 -0.1669582968795568 0.002325056792492131 -0.260279965004374 0.002325056792492131 -0.1669582968795568 -0.002325056792491796 -0.1669582968795568 0.002325056792491945 -0.260279965004374 -0.002325056792491921 -0.1669582968795568 -0.002325056792491921 -0.260279965004374 0.002325056792491945 -0.260279965004374 -0.002325056792491971 -0.1669582968795567 0.002325056792491898 -0.260279965004374 0.002325056792491898 -0.1669582968795567 -0.002325056792491971 -0.1669582968795568 0.002325056792491979 -0.260279965004374 -0.00232505679249182 -0.1669582968795568 -0.00232505679249182 -0.260279965004374 0.002325056792491979 -0.260279965004374 -0.002325056792491992 -0.1669582968795568 0.002325056792491809 -0.260279965004374 0.002325056792491809 -0.1669582968795568 -0.002325056792491992 0.1669582968795568 -0.002325056792491884 0.260279965004374 0.002325056792491937 0.1669582968795568 0.002325056792491937 0.260279965004374 -0.002325056792491884 0.260279965004374 0.002325056792492038 0.1669582968795568 -0.002325056792491915 0.260279965004374 -0.002325056792491915 0.1669582968795568 0.002325056792492038 0.1669582968795567 -0.002325056792491837 0.260279965004374 0.002325056792491989 0.1669582968795567 0.002325056792491989 0.260279965004374 -0.002325056792491837 0.260279965004374 0.002325056792491624 0.1669582968795568 -0.002325056792492082 0.260279965004374 -0.002325056792492082 0.1669582968795568 0.002325056792491624 0.1669582968795568 -0.002325056792492216 0.260279965004374 0.002325056792491724 0.1669582968795568 0.002325056792491724 0.260279965004374 -0.002325056792492216 0.260279965004374 0.002325056792492187 0.1669582968795568 -0.002325056792491759 0.260279965004374 -0.002325056792491759 0.1669582968795568 0.002325056792492187 0.260279965004374 -0.002325056792491672 0.1669582968795568 0.002325056792492129 0.1669582968795568 -0.002325056792491672 0.260279965004374 0.002325056792492129 0.260279965004374 -0.002325056792492185 0.1669582968795568 0.002325056792491629 0.1669582968795568 -0.002325056792492185 0.260279965004374 0.002325056792491629 0.260279965004374 -0.002325056792492001 0.1669582968795568 0.002325056792491855 0.1669582968795568 -0.002325056792492001 0.260279965004374 0.002325056792491855 0.260279965004374 -0.002325056792491867 0.1669582968795568 0.001641754694637294 0.1669582968795568 -0.002325056792491867 0.260279965004374 0.001641754694637294 0.260279965004374 -0.002325056792492141 0.1669582968795568 0.002325056792491735 0.1669582968795568 -0.002325056792492141 0.260279965004374 0.002325056792491735 0.260279965004374 0.001641754694637376 0.1669582968795568 0.002325056792492074 0.1669582968795568 0.001641754694637376 0.260279965004374 0.002325056792492074 0.260279965004374 -0.002325056792491717 0.1669582968795568 0.002325056792492141 0.1669582968795568 -0.002325056792491717 0.260279965004374 0.002325056792492141 + + + + + + + + + + + + + + +

0 0 1 1 2 2 1 1 0 0 3 3 4 4 2 5 5 6 2 5 4 4 0 7 3 8 6 9 1 10 6 9 3 8 7 11 8 12 9 13 10 14 9 13 8 12 11 15 7 16 12 17 6 18 12 17 7 16 13 19 14 20 10 21 15 22 10 21 14 20 8 23 13 24 16 25 12 26 16 25 13 24 17 27 18 28 14 29 15 30 14 29 18 28 19 31 20 32 16 33 17 34 16 33 20 32 21 35 22 36 19 37 18 38 19 37 22 36 23 39 24 40 21 41 20 42 21 41 24 40 25 43 26 44 23 45 22 46 23 45 26 44 27 47 28 48 25 49 24 50 25 49 28 48 29 51 30 52 27 53 26 54 27 53 30 52 31 55 32 56 29 57 28 58 29 57 32 56 33 59 34 60 31 61 30 62 31 61 34 60 35 63 36 64 33 65 32 66 33 65 36 64 37 67 38 68 35 69 34 70 35 69 38 68 39 71 40 72 37 73 36 74 37 73 40 72 41 75 42 76 38 77 43 78 38 77 42 76 39 79 40 80 44 81 41 82 44 81 40 80 45 83 46 84 43 85 47 86 43 85 46 84 42 87 45 88 48 89 44 90 48 89 45 88 49 91 50 92 47 93 51 94 47 93 50 92 46 95 52 96 53 97 54 98 53 97 52 96 55 99 55 100 51 101 53 102 51 101 55 100 50 103

+
+
+
+ + + + 0.248957885806392 9.015748031496067 -0.9291234787743667 -0.2489578858063836 9.015748031496067 -0.9291234787743667 0 9.015748031496067 -0.9618994062348557 0.4809497031174237 9.015748031496067 -0.8330293216845524 -0.4809497031174248 9.015748031496067 -0.8330293216845524 0.6801655929679815 9.015748031496067 -0.6801655929679796 -0.6801655929679813 9.015748031496067 -0.6801655929679796 0.8330293216845495 9.015748031496067 -0.4809497031174269 -0.8330293216845492 9.015748031496067 -0.4809497031174278 -0.9291234787743649 9.015748031496067 -0.2489578858063871 0.9150031055983023 9.015748031496067 -0.2830474822338055 0.929123478774365 9.015748031496067 -0.2489578858063867 -0.9618994062348564 9.015748031496067 -4.440892098500626e-016 0.9618994062348565 9.015748031496067 -2.220446049250313e-016 -0.9291234787743649 9.015748031496067 0.2489578858063863 0.929123478774365 9.015748031496067 0.2489578858063872 -0.9150031055983023 9.015748031496067 0.2830474822338065 0.8330293216845495 9.015748031496067 0.4809497031174272 -0.8330293216845492 9.015748031496067 0.4809497031174264 -0.6801655929679813 9.015748031496067 0.6801655929679789 0.6801655929679815 9.015748031496067 0.6801655929679789 0.4809497031174237 9.015748031496067 0.8330293216845512 -0.4809497031174248 9.015748031496067 0.8330293216845508 -0.2489578858063836 9.015748031496067 0.929123478774365 0.2489578858063849 9.015748031496067 0.9291234787743654 0 9.015748031496067 0.9618994062348538 + + + + + + + + + + 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 + + + + + + + + + + + + + + +

0 1 2 1 0 3 1 3 4 4 3 5 4 5 6 6 5 7 6 7 8 8 7 9 9 7 10 9 10 11 9 11 12 12 11 13 12 13 14 14 13 15 14 15 16 16 15 17 16 17 18 18 17 19 19 17 20 19 20 21 19 21 22 22 21 23 23 21 24 23 24 25

+
+
+
+ + + + -3.602577222489289 14.05346883113313 -1.22683777193248 -3.651018373051289 14.0551181102362 -1.22683777193248 + + + + + + + + + + + + + +

1 0

+
+
+
+ + + + -0.9618994062348564 8.464566929133859 -4.440892098500626e-016 -2.047068959729108 8.464566929133859 -8.311407118100078e-016 + + + + + + + + + + + + + +

1 0

+
+
+
+ + + + 0.4833919195519627 6.603578659720535 0.1210016789115732 0.5439111752678727 6.587019007461338 0.07088114243648558 0.5027872696050295 6.569984927998037 0.07088114243648558 0.5338714033075434 6.624487946513687 0.1210016789115732 0.5880425620063789 6.592829014747457 0.07088114243648558 0.5880425620063789 6.63161971485359 0.1210016789115732 0.5280637819093244 6.526204724448862 0.03242230214716624 0.5569952608241096 6.538188535394879 0.03242230214716624 0.4400442041362851 6.570316787814852 0.1210016789115732 0.4674733712283086 6.542887620722832 0.07088114243648558 0.4711994928039047 6.624696562315725 0.1793682798397561 0.5275601388107134 6.648041906275852 0.1793682798397561 0.6321739487448852 6.587019007461338 0.07088114243648558 0.6422137207052145 6.624487946513687 0.1210016789115732 0.5880425620063789 6.542275990138871 0.03242230214716624 0.5880425620063789 6.656004568349699 0.1793682798397561 0.5574989039227205 6.47522159759467 0.008246064453094726 0.572232001168075 6.481324246289459 0.008246064453094726 0.5032197577385276 6.507141234212609 0.03242230214716624 0.4067823322306055 6.526969072399174 0.1210016789115732 0.4403760639531029 6.507573722346111 0.07088114243648558 0.4228015088709469 6.587559483080193 0.1793682798397561 0.4670408830948034 6.631899485620737 0.2420033578231465 0.5254074840229848 6.656075723314809 0.2420033578231465 0.6732978544077284 6.569984927998037 0.07088114243648558 0.6926932044607952 6.603578659720535 0.1210016789115732 0.6190898631886483 6.538188535394879 0.03242230214716624 0.6485249852020374 6.648041906275852 0.1793682798397561 0.5880425620063789 6.483405746112078 0.008246064453094726 0.5880425620063789 6.664321787767905 0.2420033578231465 0.5448473064999817 6.465513685451159 0.008246064453094726 0.4841562675022786 6.482297210041816 0.03242230214716624 0.3858730454374495 6.476489588643593 0.1210016789115732 0.4233419844897952 6.466449816683268 0.07088114243648558 0.3856644296354119 6.539161499147228 0.1793682798397561 0.4169203466197189 6.593440645331421 0.2420033578231465 0.7086117527844493 6.542887620722832 0.07088114243648558 0.7360409198764728 6.570316787814852 0.1210016789115732 0.6480213421034335 6.526204724448862 0.03242230214716624 0.7048856312088461 6.624696562315725 0.1793682798397561 0.6038531228446828 6.481324246289459 0.008246064453094726 0.650677639989766 6.656075723314809 0.2420033578231465 0.5351393943564631 6.45286208802842 0.008246064453094726 0.4721724565562582 6.453365731127027 0.03242230214716624 0.378461506330396 6.420193359989591 0.1210016789115732 0.4169203466197189 6.417672634421168 0.07088114243648558 0.3623190856752814 6.48280085314042 0.1793682798397561 0.378461506330396 6.54332010885633 0.2420033578231465 0.7693027917821524 6.526969072399174 0.1210016789115732 0.735709060059655 6.507573722346107 0.07088114243648558 0.6728653662742303 6.507141234212609 0.03242230214716624 0.753283615141811 6.58755948308019 0.1793682798397561 0.6185862200900374 6.47522159759467 0.008246064453094726 0.7090442409179545 6.631899485620737 0.2420033578231465 0.5290367456616778 6.438128990783058 0.008246064453094726 0.4670408830948034 6.414387560902435 0.03242230214716624 0.4169203466197189 3.177732884575393 0.07088114243648469 0.3784615063304031 3.175212159006973 0.1210016789115725 0.3542852686363318 6.421777954325902 0.1793682798397561 0.3542852686363247 6.484953507928148 0.2420033578231465 0.7902120785753084 6.476489588643593 0.1210016789115732 0.7527431395229556 6.466449816683264 0.07088114243648558 0.6919288565104793 6.482297210041816 0.03242230214716624 0.790420694377346 6.539161499147228 0.1793682798397561 0.6312378175127762 6.465513685451159 0.008246064453094726 0.759164777393039 6.593440645331421 0.2420033578231465 0.5254074840229919 6.410562011764847 0.008246064453094726 0.4670408830948034 3.181017958094126 0.03242230214716535 0.4233419844898023 3.128955702313297 0.07088114243648469 0.3858730454374495 3.118915930352971 0.1210016789115725 0.3542852686363318 3.173627564670658 0.1793682798397552 0.346039204183235 6.422318429944758 0.2420033578231465 0.7976236176823548 6.420193359989591 0.1210016789115732 0.759164777393039 6.417672634421171 0.07088114243648558 0.7039126674564997 6.453365731127027 0.03242230214716624 0.8137660383374765 6.48280085314042 0.1793682798397561 0.6409457296562877 6.45286208802842 0.008246064453094726 0.7976236176823548 6.54332010885633 0.2420033578231465 0.5880425620063789 6.422318429944758 0.0002725696808326683 0.5860254795365592 6.421777954325902 7.771561172376096e-016 0.5880425620063718 6.406456691860113 7.771561172376096e-016 0.5254074840229919 3.184843507231713 0.008246064453093949 0.4721724565562582 3.142039787869537 0.03242230214716535 0.4403760639531029 3.087831796650457 0.07088114243648469 0.4067823322306055 3.068436446597387 0.1210016789115725 0.3623190856752814 3.112604665856141 0.1793682798397552 0.346039204183235 3.173087089051807 0.2420033578231459 0.759164777393039 3.177732884575393 0.07088114243648469 0.7976236176823548 3.17521215900697 0.1210016789115725 0.7090442409179474 6.414387560902435 0.03242230214716624 0.8217998553764261 6.421777954325906 0.1793682798397561 0.6470483783510801 6.438128990783058 0.008246064453094726 0.8217998553764332 6.484953507928148 0.2420033578231465 0.5880425620063789 3.188948827136448 0 0.5290367456616778 3.157276528213503 0.008246064453093949 0.4841562675022786 3.113108308954748 0.03242230214716535 0.4674733712283086 3.052517898273733 0.07088114243648469 0.4400442041362851 3.025088731181713 0.1210016789115725 0.3856644296354119 3.056244019849332 0.1793682798397552 0.3542852686363247 3.110452011068416 0.2420033578231459 0.7527431395229556 3.1289557023133 0.07088114243648469 0.7902120785753084 3.118915930352971 0.1210016789115725 0.7090442409179545 3.181017958094126 0.03242230214716535 0.8217998553764332 3.173627564670658 0.1793682798397552 0.650677639989766 6.410562011764847 0.008246064453094726 0.8300459198295229 6.422318429944758 0.2420033578231465 0.5860254795365663 3.173627564670658 0 0.5880425620063789 3.173087089051807 0.000272569680831336 0.5880425620063789 3.188948827136448 0 0.5880425620063718 6.406456691860113 7.771561172376096e-016 0.6506776399897731 3.184843507231713 0.008246064453093949 0.5351393943564631 3.142543430968145 0.008246064453093949 0.5032197577385276 3.088264284783955 0.03242230214716535 0.4833919195519627 2.99182685927603 0.1210016789115725 0.5027872696050295 3.025420590998527 0.07088114243648469 0.4228015088709469 3.007846035916371 0.1793682798397552 0.378461506330396 3.052085410140231 0.2420033578231459 0.735709060059655 3.087831796650457 0.07088114243648469 0.7693027917821524 3.068436446597387 0.1210016789115725 0.7039126674564997 3.142039787869537 0.03242230214716535 0.8137660383374765 3.112604665856141 0.1793682798397552 0.8300459198295229 3.173087089051807 0.2420033578231459 0.5900596444761916 6.421777954325906 7.771561172376096e-016 0.5880425620063789 6.422318429944758 0.0002725696808326683 0.5900596444761916 3.173627564670658 0 0.6470483783510801 3.157276528213503 0.008246064453093949 0.5880425620063789 3.173087089051807 0.000272569680831336 0.5448473064999817 3.129891833545402 0.008246064453093949 0.5280637819093244 3.069200794547699 0.03242230214716535 0.5338714033075434 2.970917572482877 0.1210016789115725 0.5439111752678727 3.008386511535226 0.07088114243648469 0.4711994928039047 2.970708956680836 0.1793682798397552 0.4169203466197189 3.001964873665143 0.2420033578231459 0.7086117527844493 3.052517898273733 0.07088114243648469 0.7360409198764728 3.025088731181713 0.1210016789115725 0.6919288565104864 3.113108308954748 0.03242230214716535 0.790420694377346 3.056244019849332 0.1793682798397552 0.8217998553764332 3.110452011068416 0.2420033578231459 0.5574989039227205 3.120183921401891 0.008246064453093949 0.5569952608241096 3.057216983601686 0.03242230214716535 0.5880425620063789 2.963785804142974 0.1210016789115725 0.5880425620063789 3.002576504249108 0.07088114243648469 0.5275601388107134 2.947363612720709 0.1793682798397552 0.4670408830948034 2.963506033375824 0.2420033578231459 0.6732978544077284 3.025420590998527 0.07088114243648469 0.6926932044607952 2.99182685927603 0.1210016789115725 0.6728653662742303 3.088264284783955 0.03242230214716535 0.753283615141811 3.007846035916371 0.1793682798397552 0.6409457296562948 3.142543430968145 0.008246064453093949 0.7976236176823619 3.052085410140231 0.2420033578231459 0.572232001168075 3.114081272707102 0.008246064453093949 0.5880425620063789 3.05312952885769 0.03242230214716535 0.6422137207052145 2.970917572482877 0.1210016789115725 0.6321739487448852 3.008386511535226 0.07088114243648469 0.5880425620063789 2.939400950646862 0.1793682798397552 0.5254074840229919 2.939329795681752 0.2420033578231459 0.6480213421034335 3.069200794547699 0.03242230214716535 0.7048856312088532 2.970708956680836 0.1793682798397552 0.6312378175127833 3.129891833545402 0.008246064453093949 0.759164777393039 3.001964873665143 0.2420033578231459 0.5880425620063789 3.111999772884483 0.008246064453093949 0.6190898631886483 3.057216983601686 0.03242230214716535 0.6485249852020445 2.947363612720709 0.1793682798397552 0.5880425620063789 2.931083731228659 0.2420033578231459 0.6185862200900445 3.120183921401891 0.008246064453093949 0.7090442409179545 2.963506033375824 0.2420033578231459 0.6038531228446828 3.114081272707102 0.008246064453093949 0.6506776399897731 2.939329795681752 0.2420033578231459 + + + + + + + + + + -0.4334640660138997 0.7507817855914727 -0.4984331589077694 -0.1836478117418187 0.6853829641193376 -0.7046443597570566 -0.3547803286058036 0.6144975546712339 -0.7046443597570562 -0.2243775113039415 0.8373882722621991 -0.4984331589077705 1.091275925325016e-015 0.7095606572116066 -0.7046443597570571 -2.17301671708996e-016 0.8669281320278055 -0.4984331589077714 -0.2524777544065239 0.4373042984129942 -0.8631453725296557 -0.130692102610249 0.4877495670894656 -0.8631453725296515 -0.6130107609582518 0.6130107609582455 -0.4984331589077695 -0.5017351523775082 0.5017351523775112 -0.7046443597570581 -0.483056622061766 0.8366786123435728 -0.2581185764897784 -0.2500485073049459 0.9331937336188333 -0.2581185764897801 0.1836478117418209 0.6853829641193353 -0.7046443597570582 0.2243775113039472 0.8373882722621968 -0.4984331589077717 3.46359907515036e-015 0.5049555088130463 -0.8631453725296554 -3.268324896755522e-016 0.9661132441235291 -0.2581185764897798 -0.1899418639792269 0.328988958896347 -0.9250342443566049 -0.09832114372018906 0.3669395038220317 -0.925034244356605 -0.3570574644792127 0.3570574644792083 -0.8631453725296538 -0.7507817855914717 0.4334640660139008 -0.4984331589077699 -0.61449755467123 0.3547803286058046 -0.7046443597570594 -0.6831452263138821 0.6831452263138821 -0.2581185764897785 -0.495649255145009 0.8584896926448269 -0.1316330638433547 -0.2565669338448101 0.95752083265101 -0.1316330638433571 0.3547803286058064 0.61449755467123 -0.7046443597570583 0.4334640660139043 0.7507817855914674 -0.4984331589077733 0.1306921026102521 0.4877495670894639 -0.863145372529652 0.2500485073049422 0.933193733618834 -0.2581185764897808 4.480226934616794e-015 0.3798837279584463 -0.925034244356604 -3.513250102566672e-016 0.9912985102900189 -0.1316330638433571 -0.268618360101841 0.2686183601018437 -0.9250342443566043 -0.4373042984129897 0.2524777544065203 -0.8631453725296591 -0.8373882722621975 0.2243775113039485 -0.4984331589077697 -0.6853829641193399 0.1836478117418273 -0.7046443597570522 -0.8366786123435739 0.4830566220617638 -0.2581185764897786 -0.7009538988061963 0.7009538988061946 -0.1316330638433516 0.5017351523775107 0.5017351523775072 -0.7046443597570591 0.6130107609582473 0.6130107609582423 -0.498433158907779 0.2524777544065255 0.437304298412992 -0.8631453725296564 0.4830566220617596 0.8366786123435758 -0.2581185764897805 0.09832114372019353 0.3669395038220332 -0.925034244356604 0.2565669338448102 0.9575208326510102 -0.1316330638433563 -0.3289889588963524 0.1899418639792209 -0.925034244356604 -0.4877495670894609 0.1306921026102515 -0.8631453725296541 -0.8650724726254477 0.0566998454420137 -0.4984322869082075 -0.7075597098930078 0.04637591353493175 -0.705130152227178 -0.9331937336188332 0.2500485073049485 -0.2581185764897777 -0.8584896926448288 0.4956492551450067 -0.1316330638433506 0.7507817855914638 0.4334640660138986 -0.4984331589077833 0.6144975546712321 0.3547803286058004 -0.7046443597570594 0.3570574644792157 0.3570574644792073 -0.8631453725296531 0.6831452263138831 0.6831452263138801 -0.2581185764897816 0.1899418639792281 0.3289889588963484 -0.9250342443566041 0.4956492551450166 0.8584896926448228 -0.131633063843352 -0.2989763710896034 0.07324939832375144 -0.9514450352885868 -0.50220262475222 0.0329160990611625 -0.8641232864091655 -0.7075597098930113 -0.04637591353493299 -0.7051301522271742 -0.865072472625443 -0.05669984544201184 -0.4984322869082165 -0.9640854128455849 0.06318949640755722 -0.2579658975177093 -0.9575208326510097 0.256566933844815 -0.1316330638433503 0.8373882722621913 0.2243775113039477 -0.4984331589077807 0.6853829641193321 0.1836478117418231 -0.7046443597570609 0.4373042984129922 0.2524777544065213 -0.8631453725296574 0.8366786123435733 0.4830566220617631 -0.2581185764897824 0.2686183601018456 0.2686183601018424 -0.9250342443566034 0.7009538988061935 0.7009538988061987 -0.1316330638433433 -0.2635487840530527 0.01618192014153148 -0.9645103337366016 -0.502202624752225 -0.03291609906116283 -0.8641232864091626 -0.6853829641193354 -0.1836478117418267 -0.7046443597570566 -0.8373882722621922 -0.2243775113039435 -0.4984331589077809 -0.9640854128455851 -0.06318949640755937 -0.2579658975177083 -0.9892858993695013 0.06484122355896589 -0.1308014718420756 0.8650724726254407 0.05669984544201114 -0.4984322869082197 0.7075597098930104 0.04637591353493329 -0.7051301522271751 0.4877495670894689 0.1306921026102531 -0.8631453725296491 0.9331937336188322 0.250048507304948 -0.2581185764897823 0.3289889588963529 0.1899418639792248 -0.925034244356603 0.8584896926448268 0.4956492551450136 -0.1316330638433373 -0.1325825262151339 0.0127343453502853 -0.9910901624932582 -0.1325825262151339 0.0127343453502853 -0.9910901624932582 -0.1314684721007972 0.005818595509794811 -0.9913032758897629 -0.262807686968303 -0.01722532585836541 -0.9646944634543331 -0.4877495670894708 -0.1306921026102511 -0.8631453725296483 -0.6144975546712354 -0.3547803286058019 -0.7046443597570561 -0.7507817855914635 -0.4334640660139003 -0.4984331589077827 -0.9331937336188327 -0.2500485073049525 -0.2581185764897762 -0.9892858993695027 -0.06484122355896375 -0.130801471842065 0.7075597098930132 -0.04637591353493192 -0.7051301522271724 0.8650724726254399 -0.05669984544201358 -0.4984322869082213 0.5022026247522167 0.03291609906116173 -0.8641232864091675 0.9640854128455838 0.06318949640755855 -0.2579658975177138 0.2989763710896098 0.0732493983237517 -0.9514450352885848 0.9575208326510114 0.2565669338448147 -0.1316330638433379 -0.1300206976615198 -0.007784386697888009 -0.9914807217003009 -0.2980469559637377 -0.0745511248202758 -0.9516355089154575 -0.4373042984129983 -0.2524777544065263 -0.8631453725296527 -0.5017351523775121 -0.5017351523775135 -0.7046443597570535 -0.6130107609582457 -0.613010760958239 -0.498433158907785 -0.8366786123435742 -0.4830566220617643 -0.2581185764897768 -0.9575208326510135 -0.2565669338448111 -0.1316330638433294 0.685382964119338 -0.1836478117418253 -0.7046443597570545 0.8373882722621893 -0.2243775113039459 -0.4984331589077851 0.5022026247522264 -0.03291609906116264 -0.8641232864091618 0.9640854128455846 -0.06318949640755721 -0.2579658975177111 0.2635487840530514 0.01618192014152711 -0.9645103337366019 0.9892858993695026 0.06484122355896299 -0.130801471842067 -0.1294095225512526 -0.01703708685546406 -0.9914448613738116 -0.1294095225512526 -0.01703708685546406 -0.9914448613738116 0.1300206976615144 -0.007784386697885726 -0.9914807217003016 0.1314684721007921 0.005818595509785335 -0.9913032758897636 0.2628076869683108 -0.01722532585836524 -0.9646944634543312 -0.328988958896356 -0.1899418639792227 -0.9250342443566025 -0.3570574644792187 -0.357057464479213 -0.8631453725296494 -0.4334640660138984 -0.750781785591463 -0.498433158907785 -0.3547803286058082 -0.6144975546712357 -0.7046443597570525 -0.6831452263138825 -0.6831452263138814 -0.2581185764897792 -0.8584896926448312 -0.4956492551450082 -0.1316330638433289 0.6144975546712364 -0.354780328605806 -0.7046443597570531 0.7507817855914608 -0.4334640660139006 -0.4984331589077865 0.4877495670894649 -0.130692102610251 -0.8631453725296516 0.9331937336188312 -0.2500485073049522 -0.2581185764897811 0.9892858993695036 -0.0648412235589635 -0.130801471842059 0.1325825262151333 0.01273434535026626 -0.9910901624932587 0.1325825262151333 0.01273434535026626 -0.9910901624932587 0.1294095225512511 -0.01703708685545926 -0.9914448613738118 0.2980469559637244 -0.07455112482027268 -0.9516355089154618 0.1294095225512511 -0.01703708685545926 -0.9914448613738118 -0.2686183601018432 -0.2686183601018484 -0.9250342443566023 -0.2524777544065303 -0.437304298413007 -0.8631453725296472 -0.2243775113039438 -0.8373882722621894 -0.4984331589077857 -0.1836478117418248 -0.6853829641193404 -0.7046443597570525 -0.4830566220617666 -0.8366786123435721 -0.2581185764897794 -0.7009538988061996 -0.700953898806196 -0.1316330638433261 0.5017351523775123 -0.5017351523775154 -0.7046443597570523 0.613010760958244 -0.6130107609582387 -0.4984331589077874 0.4373042984130102 -0.252477754406532 -0.8631453725296453 0.8366786123435722 -0.4830566220617651 -0.2581185764897813 0.9575208326510141 -0.2565669338448116 -0.1316330638433239 -0.1899418639792279 -0.3289889588963539 -0.9250342443566022 -0.1306921026102539 -0.487749567089466 -0.8631453725296506 4.300762252573864e-016 -0.8669281320277968 -0.4984331589077866 3.449694557329075e-016 -0.7095606572116108 -0.7046443597570529 -0.2500485073049528 -0.933193733618831 -0.2581185764897817 -0.4956492551450126 -0.8584896926448292 -0.1316330638433255 0.3547803286058083 -0.6144975546712362 -0.7046443597570519 0.4334640660138977 -0.7507817855914631 -0.4984331589077853 0.3570574644792131 -0.3570574644792118 -0.8631453725296523 0.683145226313881 -0.6831452263138815 -0.2581185764897823 0.3289889588963577 -0.1899418639792214 -0.9250342443566022 0.8584896926448308 -0.4956492551450099 -0.1316330638433251 -0.09832114372019339 -0.3669395038220376 -0.9250342443566023 2.536530754970793e-016 -0.5049555088130608 -0.863145372529647 0.224377511303944 -0.8373882722621897 -0.4984331589077852 0.1836478117418255 -0.6853829641193404 -0.7046443597570522 4.584733535726535e-016 -0.9661132441235285 -0.2581185764897819 -0.2565669338448056 -0.9575208326510151 -0.1316330638433277 0.2524777544065281 -0.4373042984130082 -0.8631453725296474 0.4830566220617655 -0.8366786123435726 -0.2581185764897805 0.2686183601018484 -0.2686183601018455 -0.9250342443566018 0.7009538988061991 -0.700953898806197 -0.1316330638433243 2.258592863464012e-016 -0.3798837279584494 -0.9250342443566026 0.1306921026102536 -0.4877495670894658 -0.8631453725296507 0.250048507304948 -0.9331937336188322 -0.2581185764897816 5.585166829721326e-016 -0.9912985102900226 -0.1316330638433289 0.1899418639792272 -0.328988958896355 -0.925034244356602 0.4956492551450115 -0.8584896926448298 -0.1316330638433249 0.09832114372019012 -0.3669395038220385 -0.9250342443566021 0.2565669338448139 -0.9575208326510131 -0.1316330638433276 + + + + + + + + + + + + + + +

0 1 2 1 0 3 3 4 1 4 3 5 1 6 2 6 1 7 8 2 9 2 8 0 10 3 0 3 10 11 5 12 4 12 5 13 4 7 1 7 4 14 11 5 3 5 11 15 7 16 6 16 7 17 2 18 9 18 2 6 19 9 20 9 19 8 21 0 8 0 21 10 22 11 10 11 22 23 13 24 12 24 13 25 12 14 4 14 12 26 15 13 5 13 15 27 14 17 7 17 14 28 23 15 11 15 23 29 6 30 18 30 6 16 9 31 20 31 9 18 32 20 33 20 32 19 34 8 19 8 34 21 35 10 21 10 35 22 25 36 24 36 25 37 12 38 26 38 12 24 27 25 13 25 27 39 26 28 14 28 26 40 29 27 15 27 29 41 18 42 31 42 18 30 20 43 33 43 20 31 44 33 45 33 44 32 46 19 32 19 46 34 47 21 34 21 47 35 36 48 49 48 36 37 24 50 38 50 24 36 39 37 25 37 39 51 26 52 40 52 26 38 41 39 27 39 41 53 31 54 43 54 31 42 33 55 45 55 33 43 44 56 57 56 44 45 58 32 44 32 58 46 59 34 46 34 59 47 49 60 61 60 49 48 36 62 50 62 36 49 37 63 48 63 37 51 38 64 52 64 38 50 53 51 39 51 53 65 43 66 55 66 43 54 55 56 45 56 55 67 57 68 69 68 57 56 58 57 70 57 58 44 71 46 58 46 71 59 61 72 73 72 61 60 49 74 62 74 49 61 48 75 60 75 48 63 50 76 64 76 50 62 51 77 63 77 51 65 78 79 54 54 80 66 80 54 79 66 67 55 67 66 81 67 68 56 68 67 82 69 83 84 83 69 68 70 69 85 69 70 57 71 70 86 70 71 58 87 72 88 72 87 73 61 89 74 89 61 73 60 90 72 90 60 75 62 91 76 91 62 74 63 92 75 92 63 77 80 81 66 81 80 93 81 82 67 82 81 94 82 83 68 83 82 95 84 96 97 96 84 83 85 84 98 84 85 69 86 85 99 85 86 70 100 88 101 88 100 87 73 102 89 102 73 87 88 90 103 90 88 72 74 104 91 104 74 89 75 105 90 105 75 92 93 94 81 94 93 106 107 94 106 104 108 109 108 104 110 94 95 82 95 94 111 95 96 83 96 95 112 113 96 114 96 113 97 98 97 115 97 98 84 99 98 116 98 99 85 117 101 118 101 117 100 102 100 119 100 102 87 101 103 120 103 101 88 89 110 104 110 89 102 103 105 121 105 103 90 91 122 123 122 104 109 104 122 91 110 124 108 124 110 125 125 126 124 111 112 95 112 111 127 112 114 96 114 112 128 129 114 130 114 129 113 131 97 113 97 131 115 116 115 132 115 116 98 133 118 134 118 133 117 119 117 135 117 119 100 118 120 136 120 118 101 110 119 125 119 110 102 120 121 137 121 120 103 127 128 112 128 127 138 128 130 114 130 128 139 140 130 141 130 140 129 142 113 129 113 142 131 143 115 131 115 143 132 134 144 133 144 134 145 135 133 146 133 135 117 134 136 147 136 134 118 125 135 148 135 125 119 136 137 149 137 136 120 138 139 128 139 138 150 139 141 130 141 139 151 152 141 153 141 152 140 154 129 140 129 154 142 155 131 142 131 155 143 145 153 144 153 145 152 146 144 156 144 146 133 147 145 134 145 147 157 148 146 158 146 148 135 147 149 159 149 147 136 150 151 139 151 150 160 161 141 151 141 161 153 162 140 152 140 162 154 163 142 154 142 163 155 156 153 161 153 156 144 157 152 145 152 157 162 158 156 164 156 158 146 159 157 147 157 159 165 166 151 160 151 166 161 167 154 162 154 167 163 164 161 166 161 164 156 165 162 157 162 165 167

+
+
+
+ + + + 5.054803886668701 4.674986000277832 2.210507294831024 5.054803886668701 5.255800392830723 2.210507294831024 5.016571053961556 4.965393196554279 2.210507294831024 5.091492155859804 4.965393196554279 2.210507294831024 5.127172113926278 4.694377008329157 2.210507294831024 5.166896880423835 4.404369574507031 2.210507294831024 5.231780457947352 4.441830125456148 2.210507294831024 5.345211082945141 4.171985981443397 2.210507294831024 5.398188302151425 4.224963200649617 2.210507294831024 5.577594676008829 3.993671778922126 2.210507294831024 5.615055226958035 4.058555356445543 2.210507294831024 5.848211101779548 3.881578785166932 2.210507294831024 5.867602109831005 3.953947012424505 2.210507294831024 6.138618298056045 3.843345952459808 2.210507294831024 6.138618298056045 3.918267054358042 2.210507294831024 6.429025494332535 3.881578785166932 2.210507294831024 6.409634486281163 3.953947012424505 2.210507294831024 6.662181369154183 4.058555356445543 2.210507294831024 6.699641920103375 3.993671778922126 2.210507294831024 6.879048293960743 4.224963200649617 2.210507294831024 6.93202551316692 4.171985981443397 2.210507294831024 7.045456138164809 4.441830125456148 2.210507294831024 7.110339715688212 4.404369574507031 2.210507294831024 7.150064482185833 4.694377008329182 2.210507294831024 7.22243270944341 4.674986000277832 2.210507294831024 7.185744440252307 4.965393196554279 2.210507294831024 5.127172113926278 5.236409384779384 2.210507294831024 5.166896880423835 5.52641681860152 2.210507294831024 5.231780457947352 5.488956267652393 2.210507294831024 5.345211082945141 5.758800411665172 2.210507294831024 5.398188302151425 5.705823192458942 2.210507294831024 5.577594676008829 5.937114614186443 2.210507294831024 5.615055226958035 5.872231036663022 2.210507294831024 5.848211101779548 6.04920760794162 2.210507294831024 5.867602109831005 5.976839380684064 2.210507294831024 6.138618298056045 6.087440440648775 2.210507294831024 6.138618298056045 6.012519338750517 2.210507294831024 6.409634486281163 5.976839380684064 2.210507294831024 6.429025494332535 6.04920760794162 2.210507294831024 6.662181369154183 5.872231036663022 2.210507294831024 6.699641920103375 5.937114614186443 2.210507294831024 6.879048293960743 5.705823192458942 2.210507294831024 6.93202551316692 5.758800411665172 2.210507294831024 7.045456138164809 5.488956267652393 2.210507294831024 7.110339715688212 5.52641681860152 2.210507294831024 7.150064482185833 5.236409384779384 2.210507294831024 7.22243270944341 5.255800392830723 2.210507294831024 7.260665542150491 4.965393196554279 2.210507294831024 + + + + + + + + + + 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 + + + + + + + + + + + + + + +

0 1 2 1 0 3 3 0 4 4 0 5 4 5 6 6 5 7 6 7 8 8 7 9 8 9 10 10 9 11 10 11 12 12 11 13 12 13 14 14 13 15 14 15 16 16 15 17 17 15 18 17 18 19 19 18 20 19 20 21 21 20 22 21 22 23 23 22 24 23 24 25 1 26 27 26 1 3 27 26 28 27 28 29 29 28 30 29 30 31 31 30 32 31 32 33 33 32 34 33 34 35 35 34 36 35 36 37 35 37 38 38 37 39 38 39 40 40 39 41 40 41 42 42 41 43 42 43 44 44 43 45 44 45 46 46 45 25 46 25 24 46 24 47

+
+
+
+ + + + 3.68971504441712 4.924634291813741 2.446727767271968 3.68971504441712 5.006152101294854 2.446727767271968 3.684349032809131 4.965393196554297 2.446727767271968 3.705447394417853 4.886653039073993 2.446727767271968 3.705447394417853 5.04413335403463 2.446727767271968 3.730473949157663 4.854037797942242 2.446727767271968 3.730473949157663 5.076748595166359 2.446727767271968 3.763089190289442 4.829011243202418 2.446727767271968 3.763089190289442 5.101775149906183 2.446727767271968 3.801070443029168 4.8132788932017 2.446727767271968 3.801070443029168 5.11750749990693 2.446727767271968 3.841829347769725 4.807912881593675 2.446727767271968 3.841829347769725 5.122873511514927 2.446727767271968 3.882588252510281 4.8132788932017 2.446727767271968 3.882588252510281 5.11750749990693 2.446727767271968 3.920569505250036 4.829011243202418 2.446727767271968 3.920569505250036 5.101775149906183 2.446727767271968 3.953184746381801 4.854037797942242 2.446727767271968 3.953184746381801 5.076748595166359 2.446727767271968 3.978211301121611 4.886653039073993 2.446727767271968 3.978211301121611 5.04413335403463 2.446727767271968 3.993943651122343 4.924634291813741 2.446727767271968 3.993943651122343 5.006152101294854 2.446727767271968 3.999309662730347 4.965393196554297 2.446727767271968 + + + + + + + + + + 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 + + + + + + + + + + + + + + +

0 1 2 1 0 3 1 3 4 4 3 5 4 5 6 6 5 7 6 7 8 8 7 9 8 9 10 10 9 11 10 11 12 12 11 13 12 13 14 14 13 15 14 15 16 16 15 17 16 17 18 18 17 19 18 19 20 20 19 21 20 21 22 22 21 23

+
+
+
+ + + + 6.409634486281163 5.976839380684064 2.367987609791654 6.662181369154183 5.872231036663022 2.210507294831024 6.409634486281163 5.976839380684064 2.210507294831024 6.662181369154183 5.872231036663022 2.367987609791654 6.138618298056045 6.012519338750517 2.367987609791654 6.138618298056045 6.012519338750517 2.210507294831024 6.879048293960743 5.705823192458942 2.210507294831024 6.879048293960743 5.705823192458942 2.367987609791654 5.867602109831005 5.976839380684064 2.367987609791654 5.867602109831005 5.976839380684064 2.210507294831024 7.045456138164809 5.488956267652393 2.367987609791654 7.045456138164809 5.488956267652393 2.210507294831024 5.615055226958035 5.872231036663022 2.367987609791654 5.615055226958035 5.872231036663022 2.210507294831024 7.150064482185833 5.236409384779384 2.367987609791654 7.150064482185833 5.236409384779384 2.210507294831024 5.398188302151425 5.705823192458942 2.367987609791654 5.398188302151425 5.705823192458942 2.210507294831024 7.185744440252307 4.965393196554279 2.367987609791654 7.185744440252307 4.965393196554279 2.210507294831024 5.231780457947352 5.488956267652393 2.210507294831024 5.231780457947352 5.488956267652393 2.367987609791654 7.150064482185833 4.694377008329182 2.367987609791654 7.150064482185833 4.694377008329182 2.210507294831024 5.127172113926278 5.236409384779384 2.210507294831024 5.127172113926278 5.236409384779384 2.367987609791654 7.045456138164809 4.441830125456148 2.367987609791654 7.045456138164809 4.441830125456148 2.210507294831024 5.091492155859804 4.965393196554279 2.210507294831024 5.091492155859804 4.965393196554279 2.367987609791654 6.879048293960743 4.224963200649617 2.367987609791654 6.879048293960743 4.224963200649617 2.210507294831024 5.127172113926278 4.694377008329157 2.210507294831024 5.127172113926278 4.694377008329157 2.367987609791654 6.662181369154183 4.058555356445543 2.210507294831024 6.662181369154183 4.058555356445543 2.367987609791654 5.231780457947352 4.441830125456148 2.210507294831024 5.231780457947352 4.441830125456148 2.367987609791654 6.409634486281163 3.953947012424505 2.210507294831024 6.409634486281163 3.953947012424505 2.367987609791654 5.398188302151425 4.224963200649617 2.210507294831024 5.398188302151425 4.224963200649617 2.367987609791654 6.138618298056045 3.918267054358042 2.210507294831024 6.138618298056045 3.918267054358042 2.367987609791654 5.615055226958035 4.058555356445543 2.367987609791654 5.615055226958035 4.058555356445543 2.210507294831024 5.867602109831005 3.953947012424505 2.210507294831024 5.867602109831005 3.953947012424505 2.367987609791654 + + + + + + + + + + 0.2588190451025039 0.9659258262890729 0 0.4999999999999815 0.8660254037844493 0 0.2588190451025039 0.9659258262890729 0 0.4999999999999815 0.8660254037844493 0 -1.285873157941851e-014 0.9999999999999999 0 -1.285873157941851e-014 0.9999999999999999 0 0.7071067811865524 0.7071067811865428 0 0.7071067811865524 0.7071067811865428 0 -0.2588190451025529 0.9659258262890597 0 -0.2588190451025529 0.9659258262890597 0 0.8660254037844504 0.4999999999999796 0 0.8660254037844504 0.4999999999999796 0 -0.4999999999999621 0.8660254037844606 0 -0.4999999999999621 0.8660254037844606 0 0.9659258262890683 0.2588190451025202 0 0.9659258262890683 0.2588190451025202 0 -0.7071067811865098 0.7071067811865854 0 -0.7071067811865098 0.7071067811865854 0 0.9999999999999999 -1.648555330694684e-015 0 0.9999999999999999 -1.648555330694684e-015 0 -0.8660254037844276 0.5000000000000192 0 -0.8660254037844276 0.5000000000000192 0 0.9659258262890704 -0.2588190451025128 0 0.9659258262890704 -0.2588190451025128 0 -0.9659258262890439 0.2588190451026116 0 -0.9659258262890439 0.2588190451026116 0 0.8660254037844514 -0.4999999999999782 0 0.8660254037844514 -0.4999999999999782 0 -1 4.838732673336347e-015 0 -1 4.838732673336347e-015 0 0.7071067811865399 -0.7071067811865551 0 0.7071067811865399 -0.7071067811865551 0 -0.9659258262890427 -0.258819045102616 0 -0.9659258262890427 -0.258819045102616 0 0.4999999999999631 -0.8660254037844599 0 0.4999999999999631 -0.8660254037844599 0 -0.8660254037844191 -0.5000000000000339 0 -0.8660254037844191 -0.5000000000000339 0 0.2588190451025165 -0.9659258262890695 0 0.2588190451025165 -0.9659258262890695 0 -0.7071067811864975 -0.7071067811865976 0 -0.7071067811864975 -0.7071067811865976 0 -1.286764268931424e-014 -1 0 -1.286764268931424e-014 -1 0 -0.4999999999999436 -0.8660254037844711 0 -0.4999999999999436 -0.8660254037844711 0 -0.2588190451025653 -0.9659258262890564 0 -0.2588190451025653 -0.9659258262890564 0 + + + + + + + + + + + + + + +

0 1 2 1 0 3 4 2 5 2 4 0 3 6 1 6 3 7 8 5 9 5 8 4 6 10 11 10 6 7 12 9 13 9 12 8 11 14 15 14 11 10 16 13 17 13 16 12 15 18 19 18 15 14 16 20 21 20 16 17 19 22 23 22 19 18 21 24 25 24 21 20 23 26 27 26 23 22 25 28 29 28 25 24 27 30 31 30 27 26 29 32 33 32 29 28 30 34 31 34 30 35 33 36 37 36 33 32 35 38 34 38 35 39 37 40 41 40 37 36 39 42 38 42 39 43 44 40 45 40 44 41 43 46 42 46 43 47 47 45 46 45 47 44

+
+
+
+ + + + 51.06260368681876 7.126416329097724 2.407357688531808 51.06260368681876 0.1184986753859647 2.486097846012126 51.06260368681876 0.1184986753859647 2.407357688531807 51.06260368681876 7.126416329097724 2.486097846012127 0.1184986753859647 7.126416329097724 2.486097846012126 51.06260368681876 7.126416329097724 2.407357688531808 0.1184986753859647 7.126416329097724 2.407357688531807 51.06260368681876 7.126416329097724 2.486097846012127 51.06260368681876 0.1184986753859647 2.486097846012126 30.70679771243117 0.1184986753859665 2.407357688531807 51.06260368681876 0.1184986753859647 2.407357688531807 30.70679771243117 0.1184986753859665 2.486097846012126 0.1184986753859647 7.126416329097724 2.486097846012126 0.1184986753859647 2.804370064010866 2.407357688531807 0.1184986753859647 2.804370064010866 2.486097846012126 0.1184986753859647 7.126416329097724 2.407357688531807 30.70679771243117 0.1184986753859665 2.486097846012126 25.61991398185795 2.804370064010866 2.407357688531807 30.70679771243117 0.1184986753859665 2.407357688531807 25.61991398185795 2.804370064010866 2.486097846012126 25.61991398185795 2.804370064010866 2.486097846012126 0.1184986753859647 2.804370064010866 2.407357688531807 25.61991398185795 2.804370064010866 2.407357688531807 0.1184986753859647 2.804370064010866 2.486097846012126 + + + + + + + + + + 1 0 0 1 0 0 1 0 0 1 0 0 0 1 0 0 1 0 0 1 0 0 1 0 -1.363521329027796e-018 -1 1.38790518535184e-045 -1.363521329027796e-018 -1 1.38790518535184e-045 -1.363521329027796e-018 -1 1.38790518535184e-045 -1.363521329027796e-018 -1 1.38790518535184e-045 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.4669118737456303 -0.8843038517135072 -0 -0.4669118737456303 -0.8843038517135072 -0 -0.4669118737456303 -0.8843038517135072 -0 -0.4669118737456303 -0.8843038517135072 -0 -1.741429659934826e-017 -1 -0 -1.741429659934826e-017 -1 -0 -1.741429659934826e-017 -1 -0 -1.741429659934826e-017 -1 -0 + + + + + + + + + + + + + + +

0 1 2 1 0 3 4 5 6 5 4 7 8 9 10 9 8 11 12 13 14 13 12 15 16 17 18 17 16 19 20 21 22 21 20 23

+
+
+
+ + + + 50.14425631911605 2.33983218444167 0.3994836727837762 25.50480608586854 2.33983218444167 0.2420033578231463 50.14425631911605 2.33983218444167 0.2420033578231463 43.53506207296286 2.33983218444167 0.3994836727837764 25.50480608586854 2.33983218444167 1.304995483807398 43.53506207296286 2.33983218444167 1.304995483807399 50.17076220141468 2.338094897130828 0.3994836727837762 50.14425631911605 2.33983218444167 0.2420033578231463 50.17076220141468 2.338094897130828 0.2420033578231463 50.14425631911605 2.33983218444167 0.3994836727837762 50.14425631911605 2.33983218444167 0.3994836727837762 43.56156795526146 2.338094897130839 0.3994836727837764 43.53506207296286 2.33983218444167 0.3994836727837764 43.58762031456511 2.332912760665932 0.3994836727837764 43.61277338778308 2.324374442838591 0.3994836727837764 43.63659679885879 2.312626036634134 0.3994836727837764 43.6586829226237 2.297868560539984 0.3994836727837764 43.67865385937673 2.280354519063662 0.3994836727837764 43.69616790085306 2.260383582310626 0.3994836727837764 43.7109253769472 2.238297458545732 0.3994836727837764 43.72267378315166 2.214474047469993 0.3994836727837764 43.73121210097899 2.189320974252054 0.3994836727837764 43.73639423744392 2.163268614948388 0.3994836727837764 43.73813152475472 2.136762732649784 0.3994836727837764 43.73813152475472 0.5508869384357507 0.3994836727837762 43.56156795526147 0.3495547739546883 0.3994836727837762 50.14425631911605 0.3478174866438408 0.3994836727837762 43.53506207296282 0.3478174866438408 0.3994836727837762 43.58762031456511 0.3547369104195806 0.3994836727837762 43.61277338778304 0.363275228246934 0.3994836727837762 43.63659679885877 0.3750236344513951 0.3994836727837762 43.6586829226237 0.3897811105455222 0.3994836727837762 43.67865385937671 0.4072951520218346 0.3994836727837762 43.69616790085306 0.4272660887748749 0.3994836727837762 43.71092537694721 0.4493522125397949 0.3994836727837762 43.72267378315161 0.4731756236155125 0.3994836727837762 43.73121210097899 0.4983286968334628 0.3994836727837762 43.7363942374439 0.5243810561371163 0.3994836727837762 50.17076220141468 2.338094897130828 0.3994836727837762 50.17076220141466 0.3495547739546492 0.3994836727837762 50.19681456071831 0.3547369104195806 0.3994836727837762 50.19681456071832 2.332912760665918 0.3994836727837762 50.22196763393623 0.3632752282469021 0.3994836727837762 50.22196763393626 2.324374442838588 0.3994836727837762 50.24579104501201 0.3750236344513791 0.3994836727837762 50.24579104501199 2.31262603663413 0.3994836727837762 50.26787716877689 2.297868560539984 0.3994836727837762 50.26787716877686 0.3897811105455418 0.3994836727837762 50.28784810552991 0.4072951520218435 0.3994836727837762 50.28784810552993 2.280354519063655 0.3994836727837762 50.30536214700624 0.427266088774882 0.3994836727837762 50.30536214700626 2.260383582310615 0.3994836727837762 50.32011962310041 0.4493522125397735 0.3994836727837762 50.32011962310039 2.238297458545718 0.3994836727837762 50.33186802930484 2.21447404747 0.3994836727837762 50.33186802930485 0.4731756236154912 0.3994836727837762 50.34040634713219 2.189320974252057 0.3994836727837762 50.3404063471322 0.4983286968334255 0.3994836727837762 50.34558848359709 2.163268614948384 0.3994836727837762 50.34558848359711 0.5243810561371145 0.3994836727837762 50.3473257709079 2.136762732649773 0.3994836727837762 50.3473257709079 0.5508869384357045 0.3994836727837762 43.56156795526146 2.338094897130839 1.304995483807399 43.53506207296286 2.33983218444167 0.3994836727837764 43.56156795526146 2.338094897130839 0.3994836727837764 43.53506207296286 2.33983218444167 1.304995483807399 43.53506207296286 2.33983218444167 1.304995483807399 29.0207414471994 0.4834205400204272 1.304995483807398 25.50480608586854 2.33983218444167 1.304995483807398 29.03406389556177 0.4743753551861669 1.304995483807398 29.04507585432682 0.4626263227489496 1.304995483807398 29.05324014512329 0.4487465765392891 1.304995483807398 29.05815850270828 0.4334131895122741 1.304995483807398 29.05959100288907 0.4173741452051463 1.304995483807398 43.53506207296282 0.3478174866438408 1.304995483807398 43.56156795526147 0.3495547739546883 1.304995483807398 43.56156795526146 2.338094897130839 1.304995483807399 43.58762031456511 2.332912760665932 1.304995483807399 43.58762031456511 0.3547369104195806 1.304995483807398 43.61277338778308 2.324374442838591 1.304995483807399 43.61277338778304 0.363275228246934 1.304995483807398 43.63659679885877 0.3750236344513951 1.304995483807398 43.63659679885879 2.312626036634134 1.304995483807399 43.6586829226237 0.3897811105455222 1.304995483807398 43.6586829226237 2.297868560539984 1.304995483807399 43.67865385937673 2.280354519063662 1.304995483807399 43.67865385937671 0.4072951520218346 1.304995483807398 43.69616790085306 0.4272660887748749 1.304995483807398 43.69616790085306 2.260383582310626 1.304995483807399 43.7109253769472 2.238297458545732 1.304995483807399 43.71092537694721 0.4493522125397949 1.304995483807398 43.72267378315166 2.214474047469993 1.304995483807399 43.72267378315161 0.4731756236155125 1.304995483807398 43.73121210097899 0.4983286968334628 1.304995483807398 43.73121210097899 2.189320974252054 1.304995483807399 43.7363942374439 0.5243810561371163 1.304995483807398 43.73639423744392 2.163268614948388 1.304995483807399 43.73813152475472 0.5508869384357507 1.304995483807398 43.73813152475472 2.136762732649784 1.304995483807399 29.01792778668387 0.3530655869813781 1.304995483807398 29.00270410638306 0.3478174866438408 1.304995483807398 29.03162811879157 0.3615274957018002 1.304995483807398 29.04313678181573 0.3727904293538451 1.304995483807398 29.05189236747371 0.3863049666688863 1.304995483807398 29.05746776635262 0.4014118500799384 1.304995483807398 25.50480608586854 2.33983218444167 1.304995483807398 0.5491086559751111 2.339832184441677 0.2420033578231463 25.50480608586854 2.33983218444167 0.2420033578231463 0.5491086559751111 2.339832184441677 2.210507294831021 25.50480608586854 2.33983218444167 2.210507294831021 50.19681456071832 2.332912760665918 0.3994836727837762 50.19681456071832 2.332912760665918 0.2420033578231463 50.22196763393626 2.324374442838588 0.3994836727837762 50.22196763393626 2.324374442838588 0.2420033578231463 50.24579104501199 2.31262603663413 0.3994836727837762 50.24579104501199 2.31262603663413 0.2420033578231463 50.26787716877689 2.297868560539984 0.3994836727837762 50.26787716877689 2.297868560539984 0.2420033578231463 50.28784810552993 2.280354519063655 0.3994836727837762 50.28784810552993 2.280354519063655 0.2420033578231463 50.30536214700626 2.260383582310615 0.2420033578231463 50.30536214700626 2.260383582310615 0.3994836727837762 50.32011962310039 2.238297458545718 0.2420033578231463 50.32011962310039 2.238297458545718 0.3994836727837762 50.33186802930484 2.21447404747 0.2420033578231463 50.33186802930484 2.21447404747 0.3994836727837762 50.34040634713219 2.189320974252057 0.2420033578231463 50.34040634713219 2.189320974252057 0.3994836727837762 50.34558848359709 2.163268614948384 0.2420033578231463 50.34558848359709 2.163268614948384 0.3994836727837762 50.3473257709079 2.136762732649773 0.2420033578231463 50.3473257709079 2.136762732649773 0.3994836727837762 50.3473257709079 2.136762732649773 0.3994836727837762 50.3473257709079 0.5508869384357045 0.2420033578231463 50.3473257709079 0.5508869384357045 0.3994836727837762 50.3473257709079 2.136762732649773 0.2420033578231463 50.3473257709079 0.5508869384357045 0.3994836727837762 50.34558848359711 0.5243810561371145 0.2420033578231463 50.34558848359711 0.5243810561371145 0.3994836727837762 50.3473257709079 0.5508869384357045 0.2420033578231463 50.3404063471322 0.4983286968334255 0.2420033578231463 50.3404063471322 0.4983286968334255 0.3994836727837762 50.33186802930485 0.4731756236154912 0.2420033578231463 50.33186802930485 0.4731756236154912 0.3994836727837762 50.32011962310041 0.4493522125397735 0.2420033578231463 50.32011962310041 0.4493522125397735 0.3994836727837762 50.30536214700624 0.427266088774882 0.2420033578231463 50.30536214700624 0.427266088774882 0.3994836727837762 50.28784810552991 0.4072951520218435 0.2420033578231463 50.28784810552991 0.4072951520218435 0.3994836727837762 50.26787716877686 0.3897811105455418 0.3994836727837762 50.26787716877686 0.3897811105455418 0.2420033578231463 50.24579104501201 0.3750236344513791 0.3994836727837762 50.24579104501201 0.3750236344513791 0.2420033578231463 50.22196763393623 0.3632752282469021 0.3994836727837762 50.22196763393623 0.3632752282469021 0.2420033578231463 50.19681456071831 0.3547369104195806 0.3994836727837762 50.19681456071831 0.3547369104195806 0.2420033578231463 50.17076220141466 0.3495547739546492 0.3994836727837762 50.17076220141466 0.3495547739546492 0.2420033578231463 50.14425631911605 0.3478174866438408 0.3994836727837762 50.14425631911605 0.3478174866438408 0.2420033578231463 29.00270410638306 0.3478174866438408 0.2420033578231463 43.53506207296282 0.3478174866438408 0.3994836727837762 50.14425631911605 0.3478174866438408 0.2420033578231463 29.00270410638306 0.3478174866438408 1.304995483807398 43.53506207296282 0.3478174866438408 1.304995483807398 50.14425631911605 0.3478174866438408 0.3994836727837762 43.53506207296282 0.3478174866438408 1.304995483807398 43.56156795526147 0.3495547739546883 0.3994836727837762 43.53506207296282 0.3478174866438408 0.3994836727837762 43.56156795526147 0.3495547739546883 1.304995483807398 43.58762031456511 0.3547369104195806 0.3994836727837762 43.58762031456511 0.3547369104195806 1.304995483807398 43.61277338778304 0.363275228246934 0.3994836727837762 43.61277338778304 0.363275228246934 1.304995483807398 43.63659679885877 0.3750236344513951 0.3994836727837762 43.63659679885877 0.3750236344513951 1.304995483807398 43.6586829226237 0.3897811105455222 0.3994836727837762 43.6586829226237 0.3897811105455222 1.304995483807398 43.67865385937671 0.4072951520218346 0.3994836727837762 43.67865385937671 0.4072951520218346 1.304995483807398 43.69616790085306 0.4272660887748749 1.304995483807398 43.69616790085306 0.4272660887748749 0.3994836727837762 43.71092537694721 0.4493522125397949 1.304995483807398 43.71092537694721 0.4493522125397949 0.3994836727837762 43.72267378315161 0.4731756236155125 1.304995483807398 43.72267378315161 0.4731756236155125 0.3994836727837762 43.73121210097899 0.4983286968334628 1.304995483807398 43.73121210097899 0.4983286968334628 0.3994836727837762 43.7363942374439 0.5243810561371163 1.304995483807398 43.7363942374439 0.5243810561371163 0.3994836727837762 43.73813152475472 0.5508869384357507 1.304995483807398 43.73813152475472 0.5508869384357507 0.3994836727837762 43.73813152475472 2.136762732649784 1.304995483807399 43.73813152475472 0.5508869384357507 0.3994836727837762 43.73813152475472 0.5508869384357507 1.304995483807398 43.73813152475472 2.136762732649784 0.3994836727837764 43.73639423744392 2.163268614948388 1.304995483807399 43.73813152475472 2.136762732649784 0.3994836727837764 43.73813152475472 2.136762732649784 1.304995483807399 43.73639423744392 2.163268614948388 0.3994836727837764 43.73121210097899 2.189320974252054 1.304995483807399 43.73121210097899 2.189320974252054 0.3994836727837764 43.72267378315166 2.214474047469993 1.304995483807399 43.72267378315166 2.214474047469993 0.3994836727837764 43.7109253769472 2.238297458545732 1.304995483807399 43.7109253769472 2.238297458545732 0.3994836727837764 43.69616790085306 2.260383582310626 1.304995483807399 43.69616790085306 2.260383582310626 0.3994836727837764 43.67865385937673 2.280354519063662 1.304995483807399 43.67865385937673 2.280354519063662 0.3994836727837764 43.6586829226237 2.297868560539984 0.3994836727837764 43.6586829226237 2.297868560539984 1.304995483807399 43.63659679885879 2.312626036634134 0.3994836727837764 43.63659679885879 2.312626036634134 1.304995483807399 43.61277338778308 2.324374442838591 0.3994836727837764 43.61277338778308 2.324374442838591 1.304995483807399 43.58762031456511 2.332912760665932 0.3994836727837764 43.58762031456511 2.332912760665932 1.304995483807399 29.00270410638306 0.3478174866438408 2.210507294831021 29.01792778668387 0.3530655869813781 1.304995483807398 29.00270410638306 0.3478174866438408 1.304995483807398 29.01792778668387 0.3530655869813781 2.210507294831021 29.03162811879157 0.3615274957018002 1.304995483807398 29.03162811879157 0.3615274957018002 2.210507294831021 29.04313678181573 0.3727904293538451 1.304995483807398 29.04313678181573 0.3727904293538451 2.210507294831021 29.05189236747371 0.3863049666688863 2.210507294831021 29.05189236747371 0.3863049666688863 1.304995483807398 29.05746776635262 0.4014118500799384 2.210507294831021 29.05746776635262 0.4014118500799384 1.304995483807398 29.05959100288907 0.4173741452051463 2.210507294831021 29.05959100288907 0.4173741452051463 1.304995483807398 29.05815850270828 0.4334131895122741 2.210507294831021 29.05815850270828 0.4334131895122741 1.304995483807398 29.05324014512329 0.4487465765392891 2.210507294831021 29.05324014512329 0.4487465765392891 1.304995483807398 29.04507585432682 0.4626263227489496 2.210507294831021 29.04507585432682 0.4626263227489496 1.304995483807398 29.03406389556177 0.4743753551861669 2.210507294831021 29.03406389556177 0.4743753551861669 1.304995483807398 29.0207414471994 0.4834205400204272 1.304995483807398 29.0207414471994 0.4834205400204272 2.210507294831021 29.0207414471994 0.4834205400204272 2.210507294831021 25.50480608586854 2.33983218444167 1.304995483807398 29.0207414471994 0.4834205400204272 1.304995483807398 25.50480608586854 2.33983218444167 2.210507294831021 0.5491086559751111 2.339832184441677 2.210507294831021 0.5226027736765033 2.338094897130853 0.2420033578231463 0.5491086559751111 2.339832184441677 0.2420033578231463 0.5226027736765033 2.338094897130853 2.210507294831021 28.98669970978262 0.3460392041831959 2.210507294831021 29.00270410638306 0.3478174866438408 0.2420033578231463 28.98669970978262 0.3460392041831959 0.2420033578231463 0.4965504143728481 2.332912760665936 0.2420033578231463 0.4965504143728481 2.332912760665936 2.210507294831021 0.5491086559751182 0.3460392041832314 2.210507294831021 28.98669970978262 0.3460392041831959 0.2420033578231463 0.5491086559751182 0.3460392041832314 0.2420033578231463 28.98669970978262 0.3460392041831959 2.210507294831021 0.4713973411548977 2.324374442838602 0.2420033578231463 0.4713973411548977 2.324374442838602 2.210507294831021 0.5226027736765104 0.3477764914940558 2.210507294831021 0.5491086559751182 0.3460392041832314 0.2420033578231463 0.5226027736765104 0.3477764914940558 0.2420033578231463 0.5491086559751182 0.3460392041832314 2.210507294831021 0.447573930079173 2.312626036634145 0.2420033578231463 0.447573930079173 2.312626036634145 2.210507294831021 0.4965504143728481 0.3529586279589729 2.210507294831021 0.4965504143728481 0.3529586279589729 0.2420033578231463 0.4254878063142726 2.297868560539994 0.2420033578231463 0.4254878063142726 2.297868560539994 2.210507294831021 0.4713973411548977 0.3614969457863069 2.210507294831021 0.4713973411548977 0.3614969457863069 0.2420033578231463 0.4055168695612395 2.280354519063669 0.2420033578231463 0.4055168695612395 2.280354519063669 2.210507294831021 0.447573930079173 0.3732453519907644 2.210507294831021 0.447573930079173 0.3732453519907644 0.2420033578231463 0.3880028280849146 2.260383582310636 2.210507294831021 0.3880028280849146 2.260383582310636 0.2420033578231463 0.4254878063142726 0.3880028280849146 2.210507294831021 0.4254878063142726 0.3880028280849146 0.2420033578231463 0.3732453519907679 2.238297458545736 2.210507294831021 0.3732453519907679 2.238297458545736 0.2420033578231463 0.4055168695612395 0.4055168695612395 2.210507294831021 0.4055168695612395 0.4055168695612395 0.2420033578231463 0.3614969457863069 2.214474047470008 2.210507294831021 0.3614969457863069 2.214474047470008 0.2420033578231463 0.3880028280849146 0.4254878063142709 0.2420033578231463 0.3880028280849146 0.4254878063142709 2.210507294831021 0.3529586279589694 2.189320974252061 2.210507294831021 0.3529586279589694 2.189320974252061 0.2420033578231463 0.3732453519907679 0.447573930079173 0.2420033578231463 0.3732453519907679 0.447573930079173 2.210507294831021 0.3477764914940522 2.163268614948402 2.210507294831021 0.3477764914940522 2.163268614948402 0.2420033578231463 0.3614969457863069 0.4713973411548995 0.2420033578231463 0.3614969457863069 0.4713973411548995 2.210507294831021 0.346039204183235 2.136762732649794 2.210507294831021 0.346039204183235 2.136762732649794 0.2420033578231463 0.3529586279589694 0.4965504143728481 0.2420033578231463 0.3529586279589694 0.4965504143728481 2.210507294831021 0.346039204183235 2.136762732649794 0.2420033578231463 0.3460392041832279 0.5491086559751146 2.210507294831021 0.3460392041832279 0.5491086559751146 0.2420033578231463 0.346039204183235 2.136762732649794 2.210507294831021 0.3477764914940522 0.5226027736765069 0.2420033578231463 0.3477764914940522 0.5226027736765069 2.210507294831021 0.3460392041832279 0.5491086559751146 0.2420033578231463 0.3460392041832279 0.5491086559751146 2.210507294831021 + + + + + + + + + + 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.1305261922203011 -0.9914448613737775 0 -0.06540312923079149 -0.9978589232385611 -0 -0.1305261922203011 -0.9914448613737775 0 -0.06540312923079149 -0.9978589232385611 -0 -1.259343480073271e-017 4.501881559435367e-017 -1 -1.259343480073271e-017 4.501881559435367e-017 -1 -1.259343480073271e-017 4.501881559435367e-017 -1 -1.259343480073271e-017 4.501881559435367e-017 -1 -1.259343480073271e-017 4.501881559435367e-017 -1 -1.259343480073271e-017 4.501881559435367e-017 -1 -1.259343480073271e-017 4.501881559435367e-017 -1 -1.259343480073271e-017 4.501881559435367e-017 -1 -1.259343480073271e-017 4.501881559435367e-017 -1 -1.259343480073271e-017 4.501881559435367e-017 -1 -1.259343480073271e-017 4.501881559435367e-017 -1 -1.259343480073271e-017 4.501881559435367e-017 -1 -1.259343480073271e-017 4.501881559435367e-017 -1 -1.259343480073271e-017 4.501881559435367e-017 -1 -1.259343480073271e-017 4.501881559435367e-017 -1 -1.259343480073271e-017 4.501881559435367e-017 -1 -1.259343480073271e-017 4.501881559435367e-017 -1 -1.259343480073271e-017 4.501881559435367e-017 -1 -1.259343480073271e-017 4.501881559435367e-017 -1 -1.259343480073271e-017 4.501881559435367e-017 -1 -1.259343480073271e-017 4.501881559435367e-017 -1 -1.259343480073271e-017 4.501881559435367e-017 -1 -1.259343480073271e-017 4.501881559435367e-017 -1 -1.259343480073271e-017 4.501881559435367e-017 -1 -1.259343480073271e-017 4.501881559435367e-017 -1 -1.259343480073271e-017 4.501881559435367e-017 -1 -1.259343480073271e-017 4.501881559435367e-017 -1 -1.259343480073271e-017 4.501881559435367e-017 -1 -1.259343480073271e-017 4.501881559435367e-017 -1 -1.259343480073271e-017 4.501881559435367e-017 -1 -1.259343480073271e-017 4.501881559435367e-017 -1 -1.259343480073271e-017 4.501881559435367e-017 -1 -1.259343480073271e-017 4.501881559435367e-017 -1 -1.259343480073271e-017 4.501881559435367e-017 -1 -1.259343480073271e-017 4.501881559435367e-017 -1 -1.259343480073271e-017 4.501881559435367e-017 -1 -1.259343480073271e-017 4.501881559435367e-017 -1 -1.259343480073271e-017 4.501881559435367e-017 -1 -1.259343480073271e-017 4.501881559435367e-017 -1 -1.259343480073271e-017 4.501881559435367e-017 -1 -1.259343480073271e-017 4.501881559435367e-017 -1 -1.259343480073271e-017 4.501881559435367e-017 -1 -1.259343480073271e-017 4.501881559435367e-017 -1 -1.259343480073271e-017 4.501881559435367e-017 -1 -1.259343480073271e-017 4.501881559435367e-017 -1 -1.259343480073271e-017 4.501881559435367e-017 -1 -1.259343480073271e-017 4.501881559435367e-017 -1 -1.259343480073271e-017 4.501881559435367e-017 -1 -1.259343480073271e-017 4.501881559435367e-017 -1 -1.259343480073271e-017 4.501881559435367e-017 -1 -1.259343480073271e-017 4.501881559435367e-017 -1 -1.259343480073271e-017 4.501881559435367e-017 -1 -0.1305261922200457 -0.9914448613738112 0 -0.06540312923042768 -0.9978589232385848 0 -0.1305261922200457 -0.9914448613738112 0 -0.06540312923042768 -0.9978589232385848 0 9.405698293996835e-018 4.12499437797971e-016 -1 9.405698293996835e-018 4.12499437797971e-016 -1 9.405698293996835e-018 4.12499437797971e-016 -1 9.405698293996835e-018 4.12499437797971e-016 -1 9.405698293996835e-018 4.12499437797971e-016 -1 9.405698293996835e-018 4.12499437797971e-016 -1 9.405698293996835e-018 4.12499437797971e-016 -1 9.405698293996835e-018 4.12499437797971e-016 -1 9.405698293996835e-018 4.12499437797971e-016 -1 9.405698293996835e-018 4.12499437797971e-016 -1 9.405698293996835e-018 4.12499437797971e-016 -1 9.405698293996835e-018 4.12499437797971e-016 -1 9.405698293996835e-018 4.12499437797971e-016 -1 9.405698293996835e-018 4.12499437797971e-016 -1 9.405698293996835e-018 4.12499437797971e-016 -1 9.405698293996835e-018 4.12499437797971e-016 -1 9.405698293996835e-018 4.12499437797971e-016 -1 9.405698293996835e-018 4.12499437797971e-016 -1 9.405698293996835e-018 4.12499437797971e-016 -1 9.405698293996835e-018 4.12499437797971e-016 -1 9.405698293996835e-018 4.12499437797971e-016 -1 9.405698293996835e-018 4.12499437797971e-016 -1 9.405698293996835e-018 4.12499437797971e-016 -1 9.405698293996835e-018 4.12499437797971e-016 -1 9.405698293996835e-018 4.12499437797971e-016 -1 9.405698293996835e-018 4.12499437797971e-016 -1 9.405698293996835e-018 4.12499437797971e-016 -1 9.405698293996835e-018 4.12499437797971e-016 -1 9.405698293996835e-018 4.12499437797971e-016 -1 9.405698293996835e-018 4.12499437797971e-016 -1 9.405698293996835e-018 4.12499437797971e-016 -1 9.405698293996835e-018 4.12499437797971e-016 -1 9.405698293996835e-018 4.12499437797971e-016 -1 9.405698293996835e-018 4.12499437797971e-016 -1 9.405698293996835e-018 4.12499437797971e-016 -1 9.405698293996835e-018 4.12499437797971e-016 -1 9.405698293996835e-018 4.12499437797971e-016 -1 9.405698293996835e-018 4.12499437797971e-016 -1 9.405698293996835e-018 4.12499437797971e-016 -1 -2.847216503390403e-016 -1 2.354039508393783e-031 -2.847216503390403e-016 -1 2.354039508393783e-031 -2.847216503390403e-016 -1 2.354039508393783e-031 -2.847216503390403e-016 -1 2.354039508393783e-031 -2.847216503390403e-016 -1 2.354039508393783e-031 -0.2588190451024253 -0.9659258262890939 0 -0.2588190451024253 -0.9659258262890939 0 -0.3826834323650169 -0.9238795325113171 0 -0.3826834323650169 -0.9238795325113171 0 -0.4999999999999031 -0.8660254037844946 0 -0.4999999999999031 -0.8660254037844946 0 -0.6087614290086439 -0.7933533402912941 0 -0.6087614290086439 -0.7933533402912941 0 -0.7071067811866093 -0.7071067811864858 0 -0.7071067811866093 -0.7071067811864858 0 -0.7933533402914218 -0.6087614290084773 0 -0.7933533402914218 -0.6087614290084773 0 -0.8660254037845377 -0.4999999999998284 0 -0.8660254037845377 -0.4999999999998284 0 -0.9238795325112122 -0.3826834323652698 0 -0.9238795325112122 -0.3826834323652698 0 -0.9659258262890901 -0.2588190451024401 0 -0.9659258262890901 -0.2588190451024401 0 -0.9914448613738833 -0.1305261922194982 0 -0.9914448613738833 -0.1305261922194982 0 -0.997858923238638 -0.06540312922961909 -0 -0.997858923238638 -0.06540312922961909 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -0.9978589232386694 0.06540312922913877 0 -0.9914448613739054 0.1305261922193298 0 -0.9914448613739054 0.1305261922193298 0 -0.9978589232386694 0.06540312922913877 0 -0.9659258262890584 0.2588190451025578 0 -0.9659258262890584 0.2588190451025578 0 -0.923879532511276 0.3826834323651157 0 -0.923879532511276 0.3826834323651157 0 -0.8660254037843593 0.5000000000001372 0 -0.8660254037843593 0.5000000000001372 0 -0.793353340290994 0.608761429009035 0 -0.793353340290994 0.608761429009035 0 -0.7071067811861586 0.7071067811869366 0 -0.7071067811861586 0.7071067811869366 0 -0.6087614290088786 0.793353340291114 0 -0.6087614290088786 0.793353340291114 0 -0.5000000000005405 0.8660254037841265 0 -0.5000000000005405 0.8660254037841265 0 -0.3826834323649039 0.9238795325113639 0 -0.3826834323649039 0.9238795325113639 0 -0.2588190451027368 0.9659258262890103 0 -0.2588190451027368 0.9659258262890103 0 -0.1305261922200789 0.9914448613738068 0 -0.1305261922200789 0.9914448613738068 0 -0.06540312922959453 0.9978589232386395 0 -0.06540312922959453 0.9978589232386395 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 -0.0654031292309547 0.9978589232385503 0 -0.1305261922200869 0.9914448613738057 0 -0.0654031292309547 0.9978589232385503 0 -0.1305261922200869 0.9914448613738057 0 -0.2588190451025692 0.9659258262890552 0 -0.2588190451025692 0.9659258262890552 0 -0.3826834323655326 0.9238795325111032 0 -0.3826834323655326 0.9238795325111032 0 -0.4999999999994493 0.8660254037847566 0 -0.4999999999994493 0.8660254037847566 0 -0.6087614290082801 0.7933533402915733 1.589264974689687e-031 -0.6087614290082801 0.7933533402915733 1.589264974689687e-031 -0.7071067811865249 0.7071067811865701 1.589264974689568e-031 -0.7071067811865249 0.7071067811865701 1.589264974689568e-031 -0.7933533402911953 0.6087614290087727 2.004146385839144e-031 -0.7933533402911953 0.6087614290087727 2.004146385839144e-031 -0.8660254037849142 0.4999999999991765 2.004146385839205e-031 -0.8660254037849142 0.4999999999991765 2.004146385839205e-031 -0.9238795325113519 0.3826834323649326 0 -0.9238795325113519 0.3826834323649326 0 -0.9659258262888851 0.2588190451032043 -2.364051849785316e-031 -0.9659258262888851 0.2588190451032043 -2.364051849785316e-031 -0.9914448613738267 0.1305261922199271 -2.364051849785246e-031 -0.9914448613738267 0.1305261922199271 -2.364051849785246e-031 -0.9978589232386241 0.0654031292298287 0 -0.9978589232386241 0.0654031292298287 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.991444861373845 -0.130526192219789 0 -0.9978589232386542 -0.06540312922937019 0 -0.9978589232386542 -0.06540312922937019 0 -0.991444861373845 -0.130526192219789 0 -0.9659258262890479 -0.2588190451025965 0 -0.9659258262890479 -0.2588190451025965 0 -0.9238795325113181 -0.3826834323650143 0 -0.9238795325113181 -0.3826834323650143 0 -0.8660254037844345 -0.5000000000000071 0 -0.8660254037844345 -0.5000000000000071 0 -0.7933533402912433 -0.6087614290087101 0 -0.7933533402912433 -0.6087614290087101 0 -0.707106781186616 -0.7071067811864791 0 -0.707106781186616 -0.7071067811864791 0 -0.6087614290086468 -0.7933533402912919 0 -0.6087614290086468 -0.7933533402912919 0 -0.5000000000000009 -0.8660254037844382 0 -0.5000000000000009 -0.8660254037844382 0 -0.3826834323651677 -0.9238795325112544 0 -0.3826834323651677 -0.9238795325112544 0 -0.2588190451023318 -0.9659258262891188 0 -0.2588190451023318 -0.9659258262891188 0 -0.2195141426946883 0.9756093178916528 -2.251662460960872e-031 -0.4283200860438445 0.9036270823140448 -2.039446246926806e-031 -0.1832544872618059 0.983065507938516 -2.276641252136103e-031 -0.4283200860438445 0.9036270823140448 -2.039446246926806e-031 -0.6162319912743373 0.7875646849180484 -1.727743062721139e-031 -0.6162319912743373 0.7875646849180484 -1.727743062721139e-031 -0.7740832592965722 0.6330838077828211 -1.331758214899901e-031 -0.7740832592965722 0.6330838077828211 -1.331758214899901e-031 -0.8941736899130333 0.4477202388404067 -8.708083845489539e-032 -0.8941736899130333 0.4477202388404067 -8.708083845489539e-032 -0.9706451080888319 0.2405162658599619 -3.673793332284476e-032 -0.9706451080888319 0.2405162658599619 -3.673793332284476e-032 -0.9997671337217909 0.02157958131462663 1.539709831518109e-032 -0.9997671337217909 0.02157958131462663 1.539709831518109e-032 -0.9801191546728204 -0.1984097846464127 6.67810384924031e-032 -0.9801191546728204 -0.1984097846464127 6.67810384924031e-032 -0.9126596261640011 -0.4087204506385578 1.149073085081814e-031 -0.9126596261640011 -0.4087204506385578 1.149073085081814e-031 -0.8006793160253677 -0.5990931754653439 1.574282432564735e-031 -0.8006793160253677 -0.5990931754653439 1.574282432564735e-031 -0.6496407765509797 -0.7602413178999415 1.9226961353246e-031 -0.6496407765509797 -0.7602413178999415 1.9226961353246e-031 -0.5617119664874528 -0.8273328633052111 2.062622892710896e-031 -0.5617119664874528 -0.8273328633052111 2.062622892710896e-031 -0.4669118737456301 -0.8843038517135073 2.177318097629222e-031 -0.4669118737456301 -0.8843038517135073 2.177318097629222e-031 -0.4669118737456301 -0.8843038517135073 2.177318097629222e-031 -0.4669118737456301 -0.8843038517135073 2.177318097629222e-031 0.0654031292301436 -0.9978589232386035 2.33560359979311e-031 0.1305261922200579 -0.9914448613738096 2.307166278009732e-031 0.0654031292301436 -0.9978589232386035 2.33560359979311e-031 0.1305261922200579 -0.9914448613738096 2.307166278009732e-031 -0.1104325181011955 0.9938836244479679 -2.317022766077274e-031 -0.1104325181011955 0.9938836244479679 -2.317022766077274e-031 -0.1104325181011955 0.9938836244479679 -2.317022766077274e-031 0.2588190451025239 -0.9659258262890675 2.220816792941599e-031 0.2588190451025239 -0.9659258262890675 2.220816792941599e-031 1.247349874666141e-015 1 -2.354039508393784e-031 1.247349874666141e-015 1 -2.354039508393784e-031 1.247349874666141e-015 1 -2.354039508393784e-031 1.247349874666141e-015 1 -2.354039508393784e-031 0.3826834323650852 -0.9238795325112886 2.096468516819501e-031 0.3826834323650852 -0.9238795325112886 2.096468516819501e-031 0.1305261922200759 0.9914448613738072 -2.360634470126157e-031 0.0654031292301361 0.997858923238604 -2.362395058420794e-031 0.1305261922200759 0.9914448613738072 -2.360634470126157e-031 0.0654031292301361 0.997858923238604 -2.362395058420794e-031 0.4999999999999988 -0.8660254037844394 1.936249083123728e-031 0.4999999999999988 -0.8660254037844394 1.936249083123728e-031 0.2588190451025202 0.9659258262890684 -2.326838321583154e-031 0.2588190451025202 0.9659258262890684 -2.326838321583154e-031 0.6087614290087232 -0.7933533402912332 1.742899890786038e-031 0.6087614290087232 -0.7933533402912332 1.742899890786038e-031 0.382683432365069 0.9238795325112953 -2.253229324236416e-031 0.382683432365069 0.9238795325112953 -2.253229324236416e-031 0.7071067811865497 -0.7071067811865455 1.519729198093864e-031 0.7071067811865497 -0.7071067811865455 1.519729198093864e-031 0.5000000000000147 0.8660254037844301 -2.141066948438753e-031 0.5000000000000147 0.8660254037844301 -2.141066948438753e-031 0.7933533402912354 -0.6087614290087204 1.270555517473774e-031 0.7933533402912354 -0.6087614290087204 1.270555517473774e-031 0.6087614290087049 0.7933533402912473 -1.992270323537472e-031 0.6087614290087049 0.7933533402912473 -1.992270323537472e-031 0.8660254037844404 -0.4999999999999971 9.996422796851562e-032 0.8660254037844404 -0.4999999999999971 9.996422796851562e-032 0.7071067811865293 0.7071067811865658 -1.809385401038751e-031 0.7071067811865293 0.7071067811865658 -1.809385401038751e-031 0.9238795325112879 -0.3826834323650874 7.116248853379323e-032 0.9238795325112879 -0.3826834323650874 7.116248853379323e-032 0.7933533402912396 0.6087614290087149 -1.595541392671784e-031 0.7933533402912396 0.6087614290087149 -1.595541392671784e-031 0.965925826289068 -0.2588190451025222 4.114313919028921e-032 0.965925826289068 -0.2588190451025222 4.114313919028921e-032 0.8660254037844386 0.4999999999999999 -1.35439722870862e-031 0.8660254037844386 0.4999999999999999 -1.35439722870862e-031 0.9914448613738105 -0.1305261922200517 1.041981932820484e-032 0.9914448613738105 -0.1305261922200517 1.041981932820484e-032 0.9238795325112905 0.3826834323650806 -1.090078952652364e-031 0.9238795325112905 0.3826834323650806 -1.090078952652364e-031 0.9978589232386037 -0.0654031292301418 -5.041778436296195e-033 0.9978589232386037 -0.0654031292301418 -5.041778436296195e-033 0.9659258262890674 0.258819045102524 -8.071091234892916e-032 0.9659258262890674 0.258819045102524 -8.071091234892916e-032 1 -3.846068690370998e-016 -2.04817865315044e-032 1 -3.846068690370998e-016 -2.04817865315044e-032 1 -3.846068690370998e-016 -2.04817865315044e-032 1 -3.846068690370998e-016 -2.04817865315044e-032 0.9914448613738091 0.1305261922200617 -5.103294334503805e-032 0.9914448613738091 0.1305261922200617 -5.103294334503805e-032 0.9978589232386044 0.06540312923013249 -3.583408847236163e-032 0.9978589232386044 0.06540312923013249 -3.583408847236163e-032 + + + + + + + + + + + + + + +

0 1 2 1 0 3 1 3 4 4 3 5 6 7 8 7 6 9 10 11 12 11 10 13 13 10 14 14 10 15 15 10 16 16 10 17 17 10 18 18 10 19 19 10 20 20 10 21 21 10 22 22 10 23 23 10 24 25 26 27 26 25 28 26 28 29 26 29 30 26 30 31 26 31 32 26 32 33 26 33 34 26 34 35 26 35 36 26 36 37 26 37 24 26 24 10 26 10 38 26 38 39 39 38 40 40 38 41 40 41 42 42 41 43 42 43 44 44 43 45 44 45 46 44 46 47 47 46 48 48 46 49 48 49 50 50 49 51 50 51 52 52 51 53 52 53 54 52 54 55 55 54 56 55 56 57 57 56 58 57 58 59 59 58 60 59 60 61 62 63 64 63 62 65 66 67 68 67 66 69 69 66 70 70 66 71 71 66 72 72 66 73 73 66 74 74 66 75 75 66 76 75 76 77 75 77 78 78 77 79 78 79 80 80 79 81 81 79 82 81 82 83 83 82 84 83 84 85 83 85 86 86 85 87 87 85 88 87 88 89 87 89 90 90 89 91 90 91 92 92 91 93 93 91 94 93 94 95 95 94 96 95 96 97 97 96 98 99 74 100 74 99 101 74 101 102 74 102 103 74 103 104 74 104 73 105 106 107 106 105 108 108 105 109 110 8 111 8 110 6 112 111 113 111 112 110 114 113 115 113 114 112 116 115 117 115 116 114 118 117 119 117 118 116 118 120 121 120 118 119 121 122 123 122 121 120 123 124 125 124 123 122 125 126 127 126 125 124 127 128 129 128 127 126 129 130 131 130 129 128 132 133 134 133 132 135 136 137 138 137 136 139 138 140 141 140 138 137 141 142 143 142 141 140 143 144 145 144 143 142 145 146 147 146 145 144 147 148 149 148 147 146 150 148 151 148 150 149 152 151 153 151 152 150 154 153 155 153 154 152 156 155 157 155 156 154 158 157 159 157 158 156 160 159 161 159 160 158 162 163 164 163 162 165 163 165 166 167 164 163 168 169 170 169 168 171 171 172 169 172 171 173 173 174 172 174 173 175 175 176 174 176 175 177 177 178 176 178 177 179 179 180 178 180 179 181 182 180 181 180 182 183 184 183 182 183 184 185 186 185 184 185 186 187 188 187 186 187 188 189 190 189 188 189 190 191 192 191 190 191 192 193 194 195 196 195 194 197 198 199 200 199 198 201 202 201 198 201 202 203 204 203 202 203 204 205 206 205 204 205 206 207 208 207 206 207 208 209 210 209 208 209 210 211 210 212 211 212 210 213 213 214 212 214 213 215 215 216 214 216 215 217 217 218 216 218 217 219 219 64 218 64 219 62 220 221 222 221 220 223 223 224 221 224 223 225 225 226 224 226 225 227 228 226 227 226 228 229 230 229 228 229 230 231 232 231 230 231 232 233 234 233 232 233 234 235 236 235 234 235 236 237 238 237 236 237 238 239 240 239 238 239 240 241 240 242 241 242 240 243 244 245 246 245 244 247 248 249 250 249 248 251 252 253 254 253 252 222 222 252 220 251 255 249 255 251 256 257 258 259 258 257 260 256 261 255 261 256 262 263 264 265 264 263 266 262 267 261 267 262 268 269 265 270 265 269 263 268 271 267 271 268 272 273 270 274 270 273 269 272 275 271 275 272 276 277 274 278 274 277 273 275 279 280 279 275 276 281 278 282 278 281 277 280 283 284 283 280 279 285 282 286 282 285 281 284 287 288 287 284 283 289 285 286 285 289 290 288 291 292 291 288 287 293 290 289 290 293 294 292 295 296 295 292 291 297 294 293 294 297 298 296 299 300 299 296 295 301 298 297 298 301 302 303 304 305 304 303 306 307 302 301 302 307 308 309 308 307 308 309 310

+
+
+
+ + + + 51.18110236220473 0 0.2420033578231452 51.18110236220473 0.7153153851313139 0.8468730150304643 51.18110236220473 0 2.407357688531807 51.18110236220473 7.244915004483692 0.2420033578231461 51.18110236220473 6.474023811682754 0.8468730150304621 51.18110236220473 6.474023811682754 1.408731047881116 51.18110236220473 0.7153153851313139 1.408731047881116 51.18110236220473 7.244915004483692 2.407357688531808 51.18110236220473 0 2.407357688531807 0 0 0.2420033578231452 51.18110236220473 0 0.2420033578231452 0 0 2.407357688531807 0.346039204183235 6.422318429944758 0.2420033578231465 0.346039204183235 2.136762732649794 0.2420033578231463 0.3460392041832279 0.5491086559751146 0.2420033578231463 0.346039204183235 3.173087089051807 0.2420033578231459 0.3542852686363247 3.110452011068416 0.2420033578231459 0.3477764914940522 2.163268614948402 0.2420033578231463 0.3529586279589694 2.189320974252061 0.2420033578231463 0.3614969457863069 2.214474047470008 0.2420033578231463 0.378461506330396 3.052085410140231 0.2420033578231459 0.3732453519907679 2.238297458545736 0.2420033578231463 0.3880028280849146 2.260383582310636 0.2420033578231463 0.4169203466197189 3.001964873665143 0.2420033578231459 0.4055168695612395 2.280354519063669 0.2420033578231463 0.4254878063142726 2.297868560539994 0.2420033578231463 0.4670408830948034 2.963506033375824 0.2420033578231459 0.447573930079173 2.312626036634145 0.2420033578231463 0.4713973411548977 2.324374442838602 0.2420033578231463 0.5254074840229919 2.939329795681752 0.2420033578231459 0.4965504143728481 2.332912760665936 0.2420033578231463 0.5226027736765033 2.338094897130853 0.2420033578231463 0.5491086559751111 2.339832184441677 0.2420033578231463 0.5880425620063789 2.931083731228659 0.2420033578231459 25.50480608586854 2.33983218444167 0.2420033578231463 0.6506776399897731 2.939329795681752 0.2420033578231459 0.7090442409179545 2.963506033375824 0.2420033578231459 0.759164777393039 3.001964873665143 0.2420033578231459 0.7976236176823619 3.052085410140231 0.2420033578231459 0.8217998553764332 3.110452011068416 0.2420033578231459 0.8300459198295229 3.173087089051807 0.2420033578231459 0 7.244915004483692 0.2420033578231452 0 0 0.2420033578231452 0.3542852686363247 6.484953507928148 0.2420033578231465 0.378461506330396 6.54332010885633 0.2420033578231465 0.4169203466197189 6.593440645331421 0.2420033578231465 0.4670408830948034 6.631899485620737 0.2420033578231465 0.5254074840229848 6.656075723314809 0.2420033578231465 0.5880425620063789 6.664321787767905 0.2420033578231465 51.18110236220473 7.244915004483692 0.2420033578231461 0.650677639989766 6.656075723314809 0.2420033578231465 0.7090442409179545 6.631899485620737 0.2420033578231465 0.759164777393039 6.593440645331421 0.2420033578231465 0.7976236176823548 6.54332010885633 0.2420033578231465 0.8217998553764332 6.484953507928148 0.2420033578231465 0.8300459198295229 6.422318429944758 0.2420033578231465 43.8785667103903 6.693733902121489 0.2420033578231468 43.85251435108663 6.688551765656571 0.2420033578231468 43.82736127786869 6.680013447829234 0.2420033578231468 43.80353786679296 6.66826504162478 0.2420033578231468 43.78145174302806 6.653507565530626 0.2420033578231468 43.76148080627502 6.635993524054301 0.2420033578231468 43.7439667647987 6.616022587301272 0.2420033578231468 43.72920928870455 6.593936463536368 0.2420033578231468 43.71746088250009 6.570113052460643 0.2420033578231468 43.70892256467276 6.544959979242696 0.2420033578231468 43.70374042820784 6.518907619939037 0.2420033578231468 50.144256319116 6.693733902121489 0.242003357823147 50.1707622014146 6.691996614810657 0.242003357823147 50.19681456071828 6.686814478345747 0.242003357823147 50.22196763393622 6.67827616051841 0.242003357823147 50.24579104501194 6.666527754313949 0.242003357823147 50.26787716877683 6.651770278219816 0.242003357823147 50.28784810552988 6.634256236743484 0.242003357823147 50.3053621470062 6.614285299990458 0.242003357823147 50.32011962310036 6.592199176225558 0.242003357823147 50.3318680293048 6.568375765149819 0.242003357823147 50.34040634713218 6.543222691931861 0.242003357823147 50.34558848359706 6.517170332628217 0.242003357823147 50.3473257709079 6.490664450329613 0.242003357823147 50.3473257709079 3.127233759244804 0.2420033578231463 50.3473257709079 2.136762732649773 0.2420033578231463 50.3473257709079 0.5508869384357045 0.2420033578231463 0.5491086559751182 0.3460392041832314 0.2420033578231463 51.18110236220473 0 0.2420033578231452 0.5226027736765104 0.3477764914940558 0.2420033578231463 0.4965504143728481 0.3529586279589729 0.2420033578231463 0.4713973411548977 0.3614969457863069 0.2420033578231463 0.447573930079173 0.3732453519907644 0.2420033578231463 0.4254878063142726 0.3880028280849146 0.2420033578231463 0.4055168695612395 0.4055168695612395 0.2420033578231463 0.3880028280849146 0.4254878063142709 0.2420033578231463 0.3732453519907679 0.447573930079173 0.2420033578231463 0.3614969457863069 0.4713973411548995 0.2420033578231463 0.3529586279589694 0.4965504143728481 0.2420033578231463 0.3477764914940522 0.5226027736765069 0.2420033578231463 28.98669970978262 0.3460392041831959 0.2420033578231463 29.00270410638306 0.3478174866438408 0.2420033578231463 50.14425631911605 0.3478174866438408 0.2420033578231463 50.17076220141466 0.3495547739546492 0.2420033578231463 50.19681456071831 0.3547369104195806 0.2420033578231463 50.22196763393623 0.3632752282469021 0.2420033578231463 50.24579104501201 0.3750236344513791 0.2420033578231463 50.26787716877686 0.3897811105455418 0.2420033578231463 50.28784810552991 0.4072951520218435 0.2420033578231463 50.30536214700624 0.427266088774882 0.2420033578231463 50.32011962310041 0.4493522125397735 0.2420033578231463 50.33186802930485 0.4731756236154912 0.2420033578231463 50.3404063471322 0.4983286968334255 0.2420033578231463 50.34558848359711 0.5243810561371145 0.2420033578231463 43.88030399770113 2.925901594763742 0.2420033578231463 50.14425631911605 2.33983218444167 0.2420033578231463 43.85425163839747 2.931083731228659 0.2420033578231463 43.82909856517952 2.939622049055986 0.2420033578231463 43.80527515410382 2.951370455260454 0.2420033578231463 43.78318903033888 2.96612793135459 0.2420033578231463 43.76321809358586 2.983641972830919 0.2420033578231463 43.74570405210953 3.003612909583955 0.2420033578231463 43.73094657601542 3.025699033348863 0.2420033578231463 43.71919816981094 3.04952244442458 0.2420033578231463 43.71065985198359 3.074675517642527 0.2420033578231463 43.70547771551868 3.10072787694619 0.2420033578231463 43.70374042820784 3.127233759244797 0.2420033578231463 43.90680987999974 2.924164307452925 0.2420033578231463 50.14425631911599 2.924164307452925 0.2420033578231463 50.17076220141464 2.925901594763753 0.2420033578231463 50.17076220141468 2.338094897130828 0.2420033578231463 50.19681456071832 2.931083731228656 0.2420033578231463 50.19681456071832 2.332912760665918 0.2420033578231463 50.22196763393622 2.939622049056018 0.2420033578231463 50.22196763393626 2.324374442838588 0.2420033578231463 50.24579104501196 2.951370455260465 0.2420033578231463 50.24579104501199 2.31262603663413 0.2420033578231463 50.26787716877688 2.966127931354594 0.2420033578231463 50.26787716877689 2.297868560539984 0.2420033578231463 50.28784810552991 2.983641972830951 0.2420033578231463 50.28784810552993 2.280354519063655 0.2420033578231463 50.3053621470062 3.003612909583973 0.2420033578231463 50.30536214700626 2.260383582310615 0.2420033578231463 50.32011962310035 3.025699033348873 0.2420033578231463 50.32011962310039 2.238297458545718 0.2420033578231463 50.33186802930481 3.049522444424609 0.2420033578231463 50.33186802930484 2.21447404747 0.2420033578231463 50.34040634713214 3.074675517642548 0.2420033578231463 50.34040634713219 2.189320974252057 0.2420033578231463 50.34558848359704 3.100727876946218 0.2420033578231463 50.34558848359709 2.163268614948384 0.2420033578231463 0 7.244915004483692 2.407357688531807 51.18110236220473 7.244915004483692 0.2420033578231461 0 7.244915004483692 0.2420033578231452 51.18110236220473 7.244915004483692 2.407357688531808 0 0 2.407357688531807 0.1184986753859647 0.2465682045726894 2.407357688531807 0 7.244915004483692 2.407357688531807 0.1195943279619485 0.2298517765885322 2.407357688531807 0.1228625387705549 0.2134213713218518 2.407357688531807 0.1282473878187176 0.1975581175621333 2.407357688531807 0.1356567388462722 0.182533439979327 2.407357688531807 0.1449638158028748 0.1686044149725046 2.407357688531807 0.1560093720213871 0.1560093720213889 2.407357688531807 0.1686044149725063 0.1449638158028765 2.407357688531807 0.1825334399793306 0.1356567388462739 2.407357688531807 0.1975581175621315 0.1282473878187194 2.407357688531807 0.2134213713218571 0.1228625387705513 2.407357688531807 0.2298517765885322 0.1195943279619485 2.407357688531807 0.2465682045726894 0.1184986753859647 2.407357688531807 51.18110236220473 0 2.407357688531807 30.0860261920037 0.1184986753859683 2.407357688531807 30.09803909744245 0.1212016043046447 2.407357688531807 30.70679771243117 0.1184986753859665 2.407357688531807 30.10330938016302 0.1244567554178957 2.407357688531807 30.10773656538716 0.1287894127682918 2.407357688531807 30.11110468898 0.1339882234195979 2.407357688531807 30.11324944927784 0.1397995822959413 2.407357688531807 30.11406622194742 0.1459400033833784 2.407357688531807 51.06260368681876 0.1184986753859647 2.407357688531807 51.06260368681876 7.126416329097724 2.407357688531808 0.1184986753859647 7.126416329097724 2.407357688531807 51.18110236220473 7.244915004483692 2.407357688531808 0.1184986753859647 2.439303184052209 2.407357688531807 0.1184986753859647 2.804370064010866 2.407357688531807 0.1195943279619485 2.456019612036366 2.407357688531807 0.1228625387705478 2.472450017303048 2.407357688531807 0.1282473878187176 2.488313271062767 2.407357688531807 0.1356567388462722 2.503337948645571 2.407357688531807 0.1449638158028748 2.517266973652395 2.407357688531807 0.1560093720213871 2.529862016603511 2.407357688531807 0.1686044149725063 2.540907572822023 2.407357688531807 0.1825334399793306 2.550214649778626 2.407357688531807 0.1975581175621315 2.557624000806181 2.407357688531807 0.21342137132185 2.56300884985435 2.407357688531807 0.2298517765885322 2.566277060662953 2.407357688531807 0.2465682045726894 2.567372713238934 2.407357688531807 25.61991398185795 2.804370064010866 2.407357688531807 25.56118838034679 2.567372713238937 2.407357688531807 30.09912146437194 0.1713469183847511 2.407357688531807 30.10848249331568 0.1633477397435232 2.407357688531807 30.11162315591949 0.1580084394959354 2.407357688531807 30.11351516370367 0.1521099485644015 2.407357688531807 0 7.244915004483692 2.407357688531807 0 0 0.2420033578231452 0 0 2.407357688531807 0 7.244915004483692 0.2420033578231452 + + + + + + + + + + 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 8.073020723831364e-018 6.076588846250485e-017 -1 0 1 0 0 1 0 0 1 0 0 1 0 -8.676819946301222e-018 -6.129667629989134e-017 1 -8.676819946301222e-018 -6.129667629989134e-017 1 -8.676819946301222e-018 -6.129667629989134e-017 1 -8.676819946301222e-018 -6.129667629989134e-017 1 -8.676819946301222e-018 -6.129667629989134e-017 1 -8.676819946301222e-018 -6.129667629989134e-017 1 -8.676819946301222e-018 -6.129667629989134e-017 1 -8.676819946301222e-018 -6.129667629989134e-017 1 -8.676819946301222e-018 -6.129667629989134e-017 1 -8.676819946301222e-018 -6.129667629989134e-017 1 -8.676819946301222e-018 -6.129667629989134e-017 1 -8.676819946301222e-018 -6.129667629989134e-017 1 -8.676819946301222e-018 -6.129667629989134e-017 1 -8.676819946301222e-018 -6.129667629989134e-017 1 -8.676819946301222e-018 -6.129667629989134e-017 1 -8.676819946301222e-018 -6.129667629989134e-017 1 -8.676819946301222e-018 -6.129667629989134e-017 1 -8.676819946301222e-018 -6.129667629989134e-017 1 -8.676819946301222e-018 -6.129667629989134e-017 1 -8.676819946301222e-018 -6.129667629989134e-017 1 -8.676819946301222e-018 -6.129667629989134e-017 1 -8.676819946301222e-018 -6.129667629989134e-017 1 -8.676819946301222e-018 -6.129667629989134e-017 1 -8.676819946301222e-018 -6.129667629989134e-017 1 -8.676819946301222e-018 -6.129667629989134e-017 1 -8.676819946301222e-018 -6.129667629989134e-017 1 -8.676819946301222e-018 -6.129667629989134e-017 1 -8.676819946301222e-018 -6.129667629989134e-017 1 -8.676819946301222e-018 -6.129667629989134e-017 1 -8.676819946301222e-018 -6.129667629989134e-017 1 -8.676819946301222e-018 -6.129667629989134e-017 1 -8.676819946301222e-018 -6.129667629989134e-017 1 -8.676819946301222e-018 -6.129667629989134e-017 1 -8.676819946301222e-018 -6.129667629989134e-017 1 -8.676819946301222e-018 -6.129667629989134e-017 1 -8.676819946301222e-018 -6.129667629989134e-017 1 -8.676819946301222e-018 -6.129667629989134e-017 1 -8.676819946301222e-018 -6.129667629989134e-017 1 -8.676819946301222e-018 -6.129667629989134e-017 1 -8.676819946301222e-018 -6.129667629989134e-017 1 -8.676819946301222e-018 -6.129667629989134e-017 1 -8.676819946301222e-018 -6.129667629989134e-017 1 -8.676819946301222e-018 -6.129667629989134e-017 1 -8.676819946301222e-018 -6.129667629989134e-017 1 -8.676819946301222e-018 -6.129667629989134e-017 1 -8.676819946301222e-018 -6.129667629989134e-017 1 -8.676819946301222e-018 -6.129667629989134e-017 1 -8.676819946301222e-018 -6.129667629989134e-017 1 -1 0 0 -1 0 0 -1 0 0 -1 0 0 + + + + + + + + + + + + + + +

0 1 2 1 0 3 1 3 4 4 3 5 2 6 7 6 2 1 7 6 5 7 5 3 8 9 10 9 8 11 12 13 14 13 12 15 16 13 15 13 16 17 17 16 18 18 16 19 19 16 20 19 20 21 21 20 22 22 20 23 22 23 24 24 23 25 25 23 26 25 26 27 27 26 28 28 26 29 28 29 30 30 29 31 31 29 32 32 29 33 32 33 34 34 33 35 34 35 36 34 36 37 34 37 38 34 38 39 34 39 40 41 12 42 12 41 43 43 41 44 44 41 45 45 41 46 46 41 47 47 41 48 48 41 49 42 12 14 48 49 50 50 49 51 51 49 52 52 49 53 53 49 54 54 49 55 55 49 56 55 56 40 40 56 57 40 57 34 34 57 58 34 58 59 34 59 60 34 60 61 34 61 62 34 62 63 34 63 64 34 64 65 34 65 66 56 49 67 67 49 68 68 49 69 69 49 70 70 49 71 71 49 72 72 49 73 73 49 74 74 49 75 75 49 76 76 49 77 77 49 78 78 49 79 79 49 80 80 49 81 81 49 82 42 83 84 83 42 85 85 42 86 86 42 87 87 42 88 88 42 89 89 42 90 90 42 91 91 42 92 92 42 93 93 42 94 94 42 95 95 42 14 84 83 96 84 96 97 84 97 98 84 98 99 84 99 100 84 100 101 84 101 102 84 102 103 84 103 104 84 104 105 84 105 106 84 106 107 84 107 108 84 108 109 84 109 82 84 82 49 34 110 111 110 34 112 112 34 113 113 34 114 114 34 115 115 34 116 116 34 117 117 34 118 118 34 119 119 34 120 120 34 121 121 34 122 122 34 66 111 110 123 111 123 124 111 124 125 111 125 126 126 125 127 126 127 128 128 127 129 128 129 130 130 129 131 130 131 132 132 131 133 132 133 134 134 133 135 134 135 136 136 135 137 136 137 138 138 137 139 138 139 140 140 139 141 140 141 142 142 141 143 142 143 144 144 143 145 144 145 146 146 145 80 146 80 81 147 148 149 148 147 150 151 152 153 152 151 154 154 151 155 155 151 156 156 151 157 157 151 158 158 151 159 159 151 160 160 151 161 161 151 162 162 151 163 163 151 164 164 151 165 165 151 166 165 166 167 167 166 168 168 166 169 168 169 170 170 169 171 171 169 172 172 169 173 173 169 174 169 166 175 175 166 176 153 177 178 177 153 152 177 152 179 177 179 180 178 177 176 178 176 166 181 180 179 180 181 182 180 182 183 180 183 184 180 184 185 180 185 186 180 186 187 180 187 188 180 188 189 180 189 190 180 190 191 180 191 192 180 192 193 193 192 194 193 194 195 193 195 169 169 195 196 169 196 197 169 197 198 169 198 174 199 200 201 200 199 202

+
+
+
+ + + + 7.185744440252307 4.965393196554279 2.367987609791654 6.138618298056045 6.012519338750517 2.367987609791654 6.138618298056045 4.965393196554279 2.367987609791654 6.409634486281163 5.976839380684064 2.367987609791654 6.662181369154183 5.872231036663022 2.367987609791654 6.879048293960743 5.705823192458942 2.367987609791654 7.045456138164809 5.488956267652393 2.367987609791654 7.150064482185833 5.236409384779384 2.367987609791654 5.127172113926278 5.236409384779384 2.367987609791654 5.091492155859804 4.965393196554279 2.367987609791654 5.231780457947352 5.488956267652393 2.367987609791654 5.398188302151425 5.705823192458942 2.367987609791654 5.615055226958035 5.872231036663022 2.367987609791654 5.867602109831005 5.976839380684064 2.367987609791654 6.409634486281163 3.953947012424505 2.367987609791654 6.138618298056045 3.918267054358042 2.367987609791654 6.662181369154183 4.058555356445543 2.367987609791654 6.879048293960743 4.224963200649617 2.367987609791654 7.045456138164809 4.441830125456148 2.367987609791654 7.150064482185833 4.694377008329182 2.367987609791654 5.127172113926278 4.694377008329157 2.367987609791654 5.231780457947352 4.441830125456148 2.367987609791654 5.398188302151425 4.224963200649617 2.367987609791654 5.615055226958035 4.058555356445543 2.367987609791654 5.867602109831005 3.953947012424505 2.367987609791654 + + + + + + + + + + 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 + + + + + + + + + + + + + + +

0 1 2 1 0 3 3 0 4 4 0 5 5 0 6 6 0 7 2 8 9 8 2 10 10 2 11 11 2 12 12 2 13 13 2 1 14 2 15 2 14 0 0 14 16 0 16 17 0 17 18 0 18 19 20 2 9 2 20 21 2 21 22 2 22 23 2 23 24 2 24 15

+
+
+
+ + + + 43.74570405210953 3.003612909583955 0.2420033578231463 43.76321809358586 2.983641972830919 0.3207435153034614 43.76321809358586 2.983641972830919 0.2420033578231463 43.74570405210953 3.003612909583955 0.3207435153034614 43.73094657601542 3.025699033348863 0.2420033578231463 43.73094657601542 3.025699033348863 0.3207435153034614 43.70892256467276 6.544959979242696 0.3207435153034618 43.70374042820784 3.127233759244797 0.3207435153034614 43.70374042820784 6.518907619939037 0.3207435153034618 43.70547771551868 3.10072787694619 0.3207435153034614 43.71065985198359 3.074675517642527 0.3207435153034614 43.71746088250009 6.570113052460643 0.3207435153034618 43.71919816981094 3.04952244442458 0.3207435153034614 43.72920928870455 6.593936463536368 0.3207435153034618 43.73094657601542 3.025699033348863 0.3207435153034614 43.73813152475472 6.515520392577111 0.3207435153034618 43.7439667647987 6.616022587301272 0.3207435153034618 43.74221309059323 6.536039809706709 0.3207435153034618 43.74930228759288 6.556923910626212 0.3207435153034618 43.76148080627502 6.635993524054301 0.3207435153034618 43.75905675770041 6.576704019276997 0.3207435153034618 43.77130959922782 6.59504169251594 0.3207435153034618 43.78145174302806 6.653507565530626 0.3207435153034618 43.78585116265949 6.611623167669842 0.3207435153034618 43.80353786679296 6.66826504162478 0.3207435153034618 43.80243263781338 6.626164731101502 0.3207435153034618 43.82077031105234 6.638417572628923 0.3207435153034618 43.82736127786869 6.680013447829234 0.3207435153034618 43.84055041970313 6.648172042736457 0.3207435153034618 43.85251435108663 6.688551765656571 0.3207435153034618 43.86143452062263 6.655261239736115 0.3207435153034618 43.8785667103903 6.693733902121489 0.3207435153034618 43.88195393775219 6.659342805574605 0.3207435153034618 50.144256319116 6.693733902121489 0.3207435153034618 50.14313047118674 6.659342805574601 0.3207435153034618 50.16626363075097 6.657826578190901 0.3207435153034618 50.1707622014146 6.691996614810657 0.3207435153034618 50.18789439118228 6.653523952425294 0.3207435153034618 50.19681456071828 6.686814478345747 0.3207435153034618 50.20877849210176 6.646434755425636 0.3207435153034618 50.22196763393622 6.67827616051841 0.3207435153034618 50.22855860075256 6.636680285318088 0.3207435153034618 50.24579104501194 6.666527754313949 0.3207435153034618 50.24689627399151 6.624427443790681 0.3207435153034618 50.26787716877683 6.651770278219816 0.3207435153034618 50.26347774914542 6.609885880359011 0.3207435153034618 50.27801931257708 6.593304405205133 0.3207435153034618 50.28784810552988 6.634256236743484 0.3207435153034618 50.29027215410449 6.574966731966187 0.3207435153034618 50.3053621470062 6.614285299990458 0.3207435153034618 50.30002662421204 6.555186623315345 0.3207435153034618 50.30711582121172 6.534302522395885 0.3207435153034618 50.32011962310036 6.592199176225558 0.3207435153034618 50.31141844697731 6.512671761964556 0.3207435153034618 50.31293467436102 6.489538602400339 0.3207435153034618 50.31293467436102 3.128359607174145 0.3207435153034614 50.32011962310035 3.025699033348873 0.3207435153034614 50.33186802930481 3.049522444424609 0.3207435153034614 50.3318680293048 6.568375765149819 0.3207435153034618 50.34040634713218 6.543222691931861 0.3207435153034618 50.34040634713214 3.074675517642548 0.3207435153034614 50.34558848359704 3.100727876946218 0.3207435153034614 50.34558848359706 6.517170332628217 0.3207435153034618 50.3473257709079 3.127233759244804 0.3207435153034614 50.3473257709079 6.490664450329613 0.3207435153034618 43.73813152475472 3.128359607174163 0.3207435153034614 43.74570405210953 3.003612909583955 0.3207435153034614 43.73964775213843 3.105226447609857 0.3207435153034614 43.74395037790404 3.083595687178518 0.3207435153034614 43.75103957490371 3.062711586259033 0.3207435153034614 43.76321809358586 2.983641972830919 0.3207435153034614 43.76079404501126 3.042931477608272 0.3207435153034614 43.77304688653869 3.02459380436923 0.3207435153034614 43.78318903033888 2.96612793135459 0.3207435153034614 43.78758844997034 3.00801232921537 0.3207435153034614 43.80527515410382 2.951370455260454 0.3207435153034614 43.80416992512419 2.993470765783732 0.3207435153034614 43.82250759836319 2.981217924256312 0.3207435153034614 43.82909856517952 2.939622049055986 0.3207435153034614 43.84228770701396 2.971463454148767 0.3207435153034614 43.85425163839747 2.931083731228659 0.3207435153034614 43.86317180793347 2.964374257149116 0.3207435153034614 43.88030399770113 2.925901594763742 0.3207435153034614 43.88480256836478 2.960071631383501 0.3207435153034614 43.90680987999974 2.924164307452925 0.3207435153034614 43.90793572792918 2.958555403999798 0.3207435153034614 50.14425631911599 2.924164307452925 0.3207435153034614 50.14313047118665 2.958555403999805 0.3207435153034614 50.166263630751 2.960071631383512 0.3207435153034614 50.17076220141464 2.925901594763753 0.3207435153034614 50.1878943911823 2.964374257149109 0.3207435153034614 50.19681456071832 2.931083731228656 0.3207435153034614 50.20877849210176 2.971463454148788 0.3207435153034614 50.22196763393622 2.939622049056018 0.3207435153034614 50.22855860075259 2.981217924256329 0.3207435153034614 50.24579104501196 2.951370455260465 0.3207435153034614 50.24689627399157 2.993470765783735 0.3207435153034614 50.26787716877688 2.966127931354594 0.3207435153034614 50.26347774914544 3.008012329215406 0.3207435153034614 50.27801931257705 3.024593804369262 0.3207435153034614 50.28784810552991 2.983641972830951 0.3207435153034614 50.2902721541045 3.042931477608265 0.3207435153034614 50.3053621470062 3.003612909583973 0.3207435153034614 50.30002662421204 3.062711586259065 0.3207435153034614 50.30711582121167 3.08359568717851 0.3207435153034614 50.31141844697729 3.105226447609864 0.3207435153034614 43.78318903033888 2.96612793135459 0.2420033578231463 43.78318903033888 2.96612793135459 0.3207435153034614 43.71919816981094 3.04952244442458 0.2420033578231463 43.71919816981094 3.04952244442458 0.3207435153034614 43.8785667103903 6.693733902121489 0.3207435153034618 43.85251435108663 6.688551765656571 0.2420033578231468 43.8785667103903 6.693733902121489 0.2420033578231468 43.85251435108663 6.688551765656571 0.3207435153034618 50.144256319116 6.693733902121489 0.242003357823147 43.8785667103903 6.693733902121489 0.3207435153034618 43.8785667103903 6.693733902121489 0.2420033578231468 50.144256319116 6.693733902121489 0.3207435153034618 50.1707622014146 6.691996614810657 0.3207435153034618 50.144256319116 6.693733902121489 0.242003357823147 50.1707622014146 6.691996614810657 0.242003357823147 50.144256319116 6.693733902121489 0.3207435153034618 50.19681456071828 6.686814478345747 0.3207435153034618 50.19681456071828 6.686814478345747 0.242003357823147 50.22196763393622 6.67827616051841 0.3207435153034618 50.22196763393622 6.67827616051841 0.242003357823147 50.24579104501194 6.666527754313949 0.3207435153034618 50.24579104501194 6.666527754313949 0.242003357823147 50.26787716877683 6.651770278219816 0.3207435153034618 50.26787716877683 6.651770278219816 0.242003357823147 50.28784810552988 6.634256236743484 0.3207435153034618 50.28784810552988 6.634256236743484 0.242003357823147 50.3053621470062 6.614285299990458 0.242003357823147 50.3053621470062 6.614285299990458 0.3207435153034618 50.32011962310036 6.592199176225558 0.242003357823147 50.32011962310036 6.592199176225558 0.3207435153034618 50.3318680293048 6.568375765149819 0.242003357823147 50.3318680293048 6.568375765149819 0.3207435153034618 50.34040634713218 6.543222691931861 0.242003357823147 50.34040634713218 6.543222691931861 0.3207435153034618 50.34558848359706 6.517170332628217 0.242003357823147 50.34558848359706 6.517170332628217 0.3207435153034618 50.3473257709079 6.490664450329613 0.242003357823147 50.3473257709079 6.490664450329613 0.3207435153034618 50.3473257709079 6.490664450329613 0.3207435153034618 50.3473257709079 3.127233759244804 0.2420033578231463 50.3473257709079 3.127233759244804 0.3207435153034614 50.3473257709079 6.490664450329613 0.242003357823147 50.3473257709079 3.127233759244804 0.3207435153034614 50.34558848359704 3.100727876946218 0.2420033578231463 50.34558848359704 3.100727876946218 0.3207435153034614 50.3473257709079 3.127233759244804 0.2420033578231463 50.34040634713214 3.074675517642548 0.2420033578231463 50.34040634713214 3.074675517642548 0.3207435153034614 50.33186802930481 3.049522444424609 0.2420033578231463 50.33186802930481 3.049522444424609 0.3207435153034614 50.32011962310035 3.025699033348873 0.2420033578231463 50.32011962310035 3.025699033348873 0.3207435153034614 50.3053621470062 3.003612909583973 0.2420033578231463 50.3053621470062 3.003612909583973 0.3207435153034614 50.28784810552991 2.983641972830951 0.2420033578231463 50.28784810552991 2.983641972830951 0.3207435153034614 50.26787716877688 2.966127931354594 0.3207435153034614 50.26787716877688 2.966127931354594 0.2420033578231463 50.24579104501196 2.951370455260465 0.3207435153034614 50.24579104501196 2.951370455260465 0.2420033578231463 50.22196763393622 2.939622049056018 0.3207435153034614 50.22196763393622 2.939622049056018 0.2420033578231463 50.19681456071832 2.931083731228656 0.3207435153034614 50.19681456071832 2.931083731228656 0.2420033578231463 50.17076220141464 2.925901594763753 0.3207435153034614 50.17076220141464 2.925901594763753 0.2420033578231463 50.14425631911599 2.924164307452925 0.3207435153034614 50.14425631911599 2.924164307452925 0.2420033578231463 43.90680987999974 2.924164307452925 0.3207435153034614 50.14425631911599 2.924164307452925 0.2420033578231463 43.90680987999974 2.924164307452925 0.2420033578231463 50.14425631911599 2.924164307452925 0.3207435153034614 43.88030399770113 2.925901594763742 0.3207435153034614 43.90680987999974 2.924164307452925 0.2420033578231463 43.88030399770113 2.925901594763742 0.2420033578231463 43.90680987999974 2.924164307452925 0.3207435153034614 43.85425163839747 2.931083731228659 0.3207435153034614 43.85425163839747 2.931083731228659 0.2420033578231463 43.82909856517952 2.939622049055986 0.3207435153034614 43.82909856517952 2.939622049055986 0.2420033578231463 43.80527515410382 2.951370455260454 0.3207435153034614 43.80527515410382 2.951370455260454 0.2420033578231463 43.71065985198359 3.074675517642527 0.2420033578231463 43.71065985198359 3.074675517642527 0.3207435153034614 43.70547771551868 3.10072787694619 0.2420033578231463 43.70547771551868 3.10072787694619 0.3207435153034614 43.70374042820784 3.127233759244797 0.2420033578231463 43.70374042820784 3.127233759244797 0.3207435153034614 43.70374042820784 6.518907619939037 0.2420033578231468 43.70374042820784 3.127233759244797 0.3207435153034614 43.70374042820784 3.127233759244797 0.2420033578231463 43.70374042820784 6.518907619939037 0.3207435153034618 43.70892256467276 6.544959979242696 0.2420033578231468 43.70374042820784 6.518907619939037 0.3207435153034618 43.70374042820784 6.518907619939037 0.2420033578231468 43.70892256467276 6.544959979242696 0.3207435153034618 43.71746088250009 6.570113052460643 0.2420033578231468 43.71746088250009 6.570113052460643 0.3207435153034618 43.72920928870455 6.593936463536368 0.2420033578231468 43.72920928870455 6.593936463536368 0.3207435153034618 43.7439667647987 6.616022587301272 0.2420033578231468 43.7439667647987 6.616022587301272 0.3207435153034618 43.76148080627502 6.635993524054301 0.2420033578231468 43.76148080627502 6.635993524054301 0.3207435153034618 43.78145174302806 6.653507565530626 0.3207435153034618 43.78145174302806 6.653507565530626 0.2420033578231468 43.80353786679296 6.66826504162478 0.3207435153034618 43.80353786679296 6.66826504162478 0.2420033578231468 43.82736127786869 6.680013447829234 0.3207435153034618 43.82736127786869 6.680013447829234 0.2420033578231468 + + + + + + + + + + 0.7933533402916123 0.6087614290082293 -2.839269561091516e-018 0.7071067811866577 0.7071067811864372 -4.052304800255538e-019 0.7071067811866577 0.7071067811864372 -4.052304800255538e-019 0.7933533402916123 0.6087614290082293 -2.839269561091516e-018 0.8660254037845894 0.4999999999997392 -4.371774209999051e-018 0.8660254037845894 0.4999999999997392 -4.371774209999051e-018 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 1.253686526074775e-017 1.239000021359714e-016 -1 0.6087614290084553 0.7933533402914387 0 0.6087614290084553 0.7933533402914387 0 0.9238795325109803 0.3826834323658299 -1.937735128933529e-018 0.9238795325109803 0.3826834323658299 -1.937735128933529e-018 0.1950903220161044 -0.9807852804032353 0 0.2588190451025379 -0.9659258262890638 0 0.1950903220161044 -0.9807852804032353 0 0.2588190451025379 -0.9659258262890638 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.1305261922199814 -0.9914448613738197 -1.709441722766725e-018 -0.06540312923029369 -0.9978589232385936 0 -0.1305261922199814 -0.9914448613738197 -1.709441722766725e-018 -0.06540312923029369 -0.9978589232385936 0 -0.2588190451024848 -0.965925826289078 -1.709441722766441e-018 -0.2588190451024848 -0.965925826289078 -1.709441722766441e-018 -0.3826834323653059 -0.9238795325111974 2.09988620339952e-030 -0.3826834323653059 -0.9238795325111974 2.09988620339952e-030 -0.5000000000000238 -0.8660254037844251 2.434039081077433e-018 -0.5000000000000238 -0.8660254037844251 2.434039081077433e-018 -0.6087614290084881 -0.7933533402914138 2.43403908107569e-018 -0.6087614290084881 -0.7933533402914138 2.43403908107569e-018 -0.7071067811864248 -0.7071067811866704 0 -0.7071067811864248 -0.7071067811866704 0 -0.7933533402911389 -0.608761429008846 -3.304682530139375e-020 -0.7933533402911389 -0.608761429008846 -3.304682530139375e-020 -0.86602540378454 -0.4999999999998244 1.931622242525208e-018 -0.86602540378454 -0.4999999999998244 1.931622242525208e-018 -0.9238795325111538 -0.3826834323654103 1.964669067822613e-018 -0.9238795325111538 -0.3826834323654103 1.964669067822613e-018 -0.9659258262890302 -0.2588190451026625 -3.87034324265203e-030 -0.9659258262890302 -0.2588190451026625 -3.87034324265203e-030 -0.9914448613738499 -0.1305261922197522 5.464717762464277e-019 -0.9914448613738499 -0.1305261922197522 5.464717762464277e-019 -0.9978589232385668 -0.06540312923070416 1.090603476451351e-018 -0.9978589232385668 -0.06540312923070416 1.090603476451351e-018 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.997858923238512 0.06540312923154031 0 -0.9914448613737562 0.1305261922204639 -1.25556995163587e-017 -0.9914448613737562 0.1305261922204639 -1.25556995163587e-017 -0.997858923238512 0.06540312923154031 0 -0.9659258262891491 0.2588190451022194 -2.671923207551682e-017 -0.9659258262891491 0.2588190451022194 -2.671923207551682e-017 -0.9238795325113063 0.3826834323650429 -2.969255619214416e-017 -0.9238795325113063 0.3826834323650429 -2.969255619214416e-017 -0.8660254037844481 0.4999999999999837 -3.215783243998619e-017 -0.8660254037844481 0.4999999999999837 -3.215783243998619e-017 -0.7933533402914977 0.6087614290083787 -3.407287925893871e-017 -0.7933533402914977 0.6087614290083787 -3.407287925893871e-017 -0.707106781187135 0.70710678118596 -3.54049296669877e-017 -0.707106781187135 0.70710678118596 -3.54049296669877e-017 -0.6087614290086183 0.7933533402913137 -3.61311919123416e-017 -0.6087614290086183 0.7933533402913137 -3.61311919123416e-017 -0.4999999999992923 0.8660254037848472 -3.623923944660778e-017 -0.4999999999992923 0.8660254037848472 -3.623923944660778e-017 -0.3826834323655242 0.9238795325111068 -3.5727223546533e-017 -0.3826834323655242 0.9238795325111068 -3.5727223546533e-017 -0.2588190451029578 0.9659258262889511 -3.460390494611714e-017 -0.2588190451029578 0.9659258262889511 -3.460390494611714e-017 -0.1305261922198164 0.9914448613738415 -3.28885039380478e-017 -0.1305261922198164 0.9914448613738415 -3.28885039380478e-017 -0.06540312923028883 0.997858923238594 -3.181756156529731e-017 -0.06540312923028883 0.997858923238594 -3.181756156529731e-017 7.119727827482288e-017 1 9.714463744566149e-032 7.119727827482288e-017 1 9.714463744566149e-032 7.119727827482288e-017 1 9.714463744566149e-032 7.119727827482288e-017 1 9.714463744566149e-032 0.1305261922199325 0.991444861373826 0 0.06540312922994411 0.9978589232386166 0 0.1305261922199325 0.991444861373826 0 0.06540312922994411 0.9978589232386166 0 0.2588190451023891 0.9659258262891036 0 0.2588190451023891 0.9659258262891036 0 0.3826834323652765 0.9238795325112095 0 0.3826834323652765 0.9238795325112095 0 0.4999999999998007 0.8660254037845535 0 0.4999999999998007 0.8660254037845535 0 0.9659258262889898 0.2588190451028135 1.709441722768831e-018 0.9659258262889898 0.2588190451028135 1.709441722768831e-018 0.9914448613738075 0.1305261922200738 1.162969946518176e-018 0.9914448613738075 0.1305261922200738 1.162969946518176e-018 0.9978589232385846 0.06540312923043123 -1.09060347645937e-018 0.9978589232385846 0.06540312923043123 -1.09060347645937e-018 1 0 0 1 0 0 1 0 0 1 0 0 0.9659258262890843 -0.2588190451024607 0 0.9807852804032251 -0.1950903220161558 0 0.9807852804032251 -0.1950903220161558 0 0.9659258262890843 -0.2588190451024607 0 0.9238795325112964 -0.3826834323650665 0 0.9238795325112964 -0.3826834323650665 0 0.8660254037844343 -0.5000000000000074 0 0.8660254037844343 -0.5000000000000074 0 0.7933533402912668 -0.6087614290086795 0 0.7933533402912668 -0.6087614290086795 0 0.7071067811865319 -0.707106781186563 0 0.7071067811865319 -0.707106781186563 0 0.6087614290087205 -0.7933533402912352 0 0.6087614290087205 -0.7933533402912352 0 0.4999999999999814 -0.8660254037844494 0 0.4999999999999814 -0.8660254037844494 0 0.382683432365068 -0.9238795325112958 0 0.382683432365068 -0.9238795325112958 0 + + + + + + + + + + + + + + +

0 1 2 1 0 3 4 3 0 3 4 5 6 7 8 7 6 9 9 6 10 10 6 11 10 11 12 12 11 13 12 13 14 14 13 15 15 13 16 15 16 17 17 16 18 18 16 19 18 19 20 20 19 21 21 19 22 21 22 23 23 22 24 23 24 25 25 24 26 26 24 27 26 27 28 28 27 29 28 29 30 30 29 31 30 31 32 32 31 33 32 33 34 34 33 35 35 33 36 35 36 37 37 36 38 37 38 39 39 38 40 39 40 41 41 40 42 41 42 43 43 42 44 43 44 45 45 44 46 46 44 47 46 47 48 48 47 49 48 49 50 50 49 51 51 49 52 51 52 53 53 52 54 54 52 55 55 52 56 56 52 57 57 52 58 57 58 59 57 59 60 60 59 61 61 59 62 61 62 63 63 62 64 14 65 66 65 14 15 66 65 67 66 67 68 66 68 69 66 69 70 70 69 71 70 71 72 70 72 73 73 72 74 73 74 75 75 74 76 75 76 77 75 77 78 78 77 79 78 79 80 80 79 81 80 81 82 82 81 83 82 83 84 84 83 85 84 85 86 86 85 87 86 87 88 86 88 89 89 88 90 89 90 91 91 90 92 91 92 93 93 92 94 93 94 95 95 94 96 95 96 97 97 96 98 97 98 99 97 99 100 100 99 101 100 101 102 102 101 103 102 103 104 102 104 56 56 104 105 56 105 55 1 106 2 106 1 107 108 5 4 5 108 109 110 111 112 111 110 113 114 115 116 115 114 117 118 119 120 119 118 121 122 120 123 120 122 118 124 123 125 123 124 122 126 125 127 125 126 124 128 127 129 127 128 126 130 129 131 129 130 128 130 132 133 132 130 131 133 134 135 134 133 132 135 136 137 136 135 134 137 138 139 138 137 136 139 140 141 140 139 138 141 142 143 142 141 140 144 145 146 145 144 147 148 149 150 149 148 151 150 152 153 152 150 149 153 154 155 154 153 152 155 156 157 156 155 154 157 158 159 158 157 156 159 160 161 160 159 158 162 160 163 160 162 161 164 163 165 163 164 162 166 165 167 165 166 164 168 167 169 167 168 166 170 169 171 169 170 168 172 171 173 171 172 170 174 175 176 175 174 177 178 179 180 179 178 181 182 180 183 180 182 178 184 183 185 183 184 182 186 185 187 185 186 184 107 187 106 187 107 186 188 109 108 109 188 189 190 189 188 189 190 191 192 191 190 191 192 193 194 195 196 195 194 197 198 199 200 199 198 201 202 201 198 201 202 203 204 203 202 203 204 205 206 205 204 205 206 207 208 207 206 207 208 209 210 208 211 208 210 209 212 211 213 211 212 210 214 213 215 213 214 212 113 215 111 215 113 214

+
+
+
+ + + + 6.93202551316692 5.758800411665172 2.486097846012126 6.699641920103375 5.937114614186443 2.210507294831024 6.93202551316692 5.758800411665172 2.210507294831024 6.699641920103375 5.937114614186443 2.486097846012126 6.429025494332535 6.04920760794162 2.210507294831024 6.429025494332535 6.04920760794162 2.486097846012126 7.110339715688212 5.52641681860152 2.210507294831024 7.110339715688212 5.52641681860152 2.486097846012126 6.138618298056045 6.087440440648775 2.210507294831024 6.138618298056045 6.087440440648775 2.486097846012126 7.22243270944341 5.255800392830723 2.210507294831024 7.22243270944341 5.255800392830723 2.486097846012126 5.848211101779548 6.04920760794162 2.210507294831024 5.848211101779548 6.04920760794162 2.486097846012126 7.260665542150491 4.965393196554279 2.210507294831024 7.260665542150491 4.965393196554279 2.486097846012126 5.577594676008829 5.937114614186443 2.210507294831024 5.577594676008829 5.937114614186443 2.486097846012126 7.22243270944341 4.674986000277832 2.210507294831024 7.22243270944341 4.674986000277832 2.486097846012126 5.345211082945141 5.758800411665172 2.210507294831024 5.345211082945141 5.758800411665172 2.486097846012126 7.110339715688212 4.404369574507031 2.210507294831024 7.110339715688212 4.404369574507031 2.486097846012126 5.166896880423835 5.52641681860152 2.486097846012126 5.166896880423835 5.52641681860152 2.210507294831024 6.93202551316692 4.171985981443397 2.210507294831024 6.93202551316692 4.171985981443397 2.486097846012126 5.054803886668701 5.255800392830723 2.486097846012126 5.054803886668701 5.255800392830723 2.210507294831024 6.699641920103375 3.993671778922126 2.486097846012126 6.699641920103375 3.993671778922126 2.210507294831024 5.016571053961556 4.965393196554279 2.486097846012126 5.016571053961556 4.965393196554279 2.210507294831024 6.429025494332535 3.881578785166932 2.486097846012126 6.429025494332535 3.881578785166932 2.210507294831024 5.054803886668701 4.674986000277832 2.486097846012126 5.054803886668701 4.674986000277832 2.210507294831024 6.138618298056045 3.843345952459808 2.486097846012126 6.138618298056045 3.843345952459808 2.210507294831024 5.166896880423835 4.404369574507031 2.486097846012126 5.166896880423835 4.404369574507031 2.210507294831024 5.848211101779548 3.881578785166932 2.486097846012126 5.848211101779548 3.881578785166932 2.210507294831024 5.345211082945141 4.171985981443397 2.486097846012126 5.345211082945141 4.171985981443397 2.210507294831024 5.577594676008829 3.993671778922126 2.486097846012126 5.577594676008829 3.993671778922126 2.210507294831024 + + + + + + + + + + -0.7071067811866061 -0.707106781186489 0 -0.5000000000000493 -0.8660254037844102 0 -0.7071067811866061 -0.707106781186489 0 -0.5000000000000493 -0.8660254037844102 0 -0.2588190451024628 -0.9659258262890837 0 -0.2588190451024628 -0.9659258262890837 0 -0.8660254037844264 -0.5000000000000211 0 -0.8660254037844264 -0.5000000000000211 0 -6.104110278518137e-015 -1 0 -6.104110278518137e-015 -1 0 -0.9659258262890954 -0.2588190451024193 0 -0.9659258262890954 -0.2588190451024193 0 0.2588190451025422 -0.9659258262890624 0 0.2588190451025422 -0.9659258262890624 0 -1 0 0 -1 0 0 0.500000000000004 -0.8660254037844363 0 0.500000000000004 -0.8660254037844363 0 -0.9659258262890966 0.2588190451024151 0 -0.9659258262890966 0.2588190451024151 0 0.7071067811864806 -0.7071067811866143 0 0.7071067811864806 -0.7071067811866143 0 -0.866025403784418 0.5000000000000358 0 -0.866025403784418 0.5000000000000358 0 0.8660254037844507 -0.4999999999999791 0 0.8660254037844507 -0.4999999999999791 0 -0.7071067811865911 0.7071067811865041 0 -0.7071067811865911 0.7071067811865041 0 0.9659258262890937 -0.2588190451024254 0 0.9659258262890937 -0.2588190451024254 0 -0.5000000000000769 0.8660254037843943 0 -0.5000000000000769 0.8660254037843943 0 1 0 0 1 0 0 -0.2588190451024495 0.9659258262890874 0 -0.2588190451024495 0.9659258262890874 0 0.965925826289095 0.2588190451024211 0 0.965925826289095 0.2588190451024211 0 -5.997176959770302e-015 1 0 -5.997176959770302e-015 1 0 0.8660254037844425 0.4999999999999936 0 0.8660254037844425 0.4999999999999936 0 0.2588190451025288 0.9659258262890662 0 0.2588190451025288 0.9659258262890662 0 0.707106781186466 0.7071067811866292 0 0.707106781186466 0.7071067811866292 0 0.5000000000000314 0.8660254037844204 0 0.5000000000000314 0.8660254037844204 0 + + + + + + + + + + + + + + +

0 1 2 1 0 3 3 4 1 4 3 5 0 6 7 6 0 2 5 8 4 8 5 9 7 10 11 10 7 6 9 12 8 12 9 13 11 14 15 14 11 10 13 16 12 16 13 17 15 18 19 18 15 14 17 20 16 20 17 21 19 22 23 22 19 18 20 24 25 24 20 21 23 26 27 26 23 22 25 28 29 28 25 24 30 26 31 26 30 27 29 32 33 32 29 28 34 31 35 31 34 30 33 36 37 36 33 32 38 35 39 35 38 34 37 40 41 40 37 36 42 39 43 39 42 38 41 44 45 44 41 40 46 43 47 43 46 42 44 47 45 47 44 46

+
+
+
+ + + + 3.882588252510281 4.8132788932017 2.486097846012126 3.920569505250036 4.829011243202418 2.446727767271968 3.882588252510281 4.8132788932017 2.446727767271968 3.920569505250036 4.829011243202418 2.486097846012126 3.953184746381801 4.854037797942242 2.446727767271968 3.953184746381801 4.854037797942242 2.486097846012126 3.841829347769725 4.807912881593675 2.486097846012126 3.841829347769725 4.807912881593675 2.446727767271968 3.978211301121611 4.886653039073993 2.486097846012126 3.978211301121611 4.886653039073993 2.446727767271968 3.801070443029168 4.8132788932017 2.486097846012126 3.801070443029168 4.8132788932017 2.446727767271968 3.993943651122343 4.924634291813741 2.486097846012126 3.993943651122343 4.924634291813741 2.446727767271968 3.763089190289442 4.829011243202418 2.486097846012126 3.763089190289442 4.829011243202418 2.446727767271968 3.999309662730347 4.965393196554297 2.486097846012126 3.999309662730347 4.965393196554297 2.446727767271968 3.730473949157663 4.854037797942242 2.486097846012126 3.730473949157663 4.854037797942242 2.446727767271968 3.993943651122343 5.006152101294854 2.486097846012126 3.993943651122343 5.006152101294854 2.446727767271968 3.705447394417853 4.886653039073993 2.446727767271968 3.705447394417853 4.886653039073993 2.486097846012126 3.978211301121611 5.04413335403463 2.486097846012126 3.978211301121611 5.04413335403463 2.446727767271968 3.68971504441712 4.924634291813741 2.446727767271968 3.68971504441712 4.924634291813741 2.486097846012126 3.953184746381801 5.076748595166359 2.486097846012126 3.953184746381801 5.076748595166359 2.446727767271968 3.684349032809131 4.965393196554297 2.446727767271968 3.684349032809131 4.965393196554297 2.486097846012126 3.920569505250036 5.101775149906183 2.446727767271968 3.920569505250036 5.101775149906183 2.486097846012126 3.68971504441712 5.006152101294854 2.446727767271968 3.68971504441712 5.006152101294854 2.486097846012126 3.882588252510281 5.11750749990693 2.446727767271968 3.882588252510281 5.11750749990693 2.486097846012126 3.705447394417853 5.04413335403463 2.446727767271968 3.705447394417853 5.04413335403463 2.486097846012126 3.841829347769725 5.122873511514927 2.446727767271968 3.841829347769725 5.122873511514927 2.486097846012126 3.730473949157663 5.076748595166359 2.446727767271968 3.730473949157663 5.076748595166359 2.486097846012126 3.801070443029168 5.11750749990693 2.446727767271968 3.801070443029168 5.11750749990693 2.486097846012126 3.763089190289442 5.101775149906183 2.486097846012126 3.763089190289442 5.101775149906183 2.446727767271968 + + + + + + + + + + -0.2588190451025471 0.9659258262890613 0 -0.5000000000000653 0.866025403784401 0 -0.2588190451025471 0.9659258262890613 0 -0.5000000000000653 0.866025403784401 0 -0.7071067811864877 0.7071067811866073 0 -0.7071067811864877 0.7071067811866073 0 0 1 0 0 1 0 -0.866025403784455 0.4999999999999716 0 -0.866025403784455 0.4999999999999716 0 0.2588190451025471 0.9659258262890613 0 0.2588190451025471 0.9659258262890613 0 -0.9659258262891083 0.2588190451023718 0 -0.9659258262891083 0.2588190451023718 0 0.5000000000000653 0.866025403784401 0 0.5000000000000653 0.866025403784401 0 -1 1.129037623778454e-014 0 -1 1.129037623778454e-014 0 0.7071067811864877 0.7071067811866073 0 0.7071067811864877 0.7071067811866073 0 -0.9659258262891111 -0.2588190451023609 0 -0.9659258262891111 -0.2588190451023609 0 0.866025403784455 0.4999999999999716 0 0.866025403784455 0.4999999999999716 0 -0.8660254037844287 -0.500000000000017 0 -0.8660254037844287 -0.500000000000017 0 0.9659258262891083 0.2588190451023718 0 0.9659258262891083 0.2588190451023718 0 -0.7071067811864505 -0.7071067811866446 0 -0.7071067811864505 -0.7071067811866446 0 1 1.129037623778454e-014 0 1 1.129037623778454e-014 0 -0.5000000000000653 -0.866025403784401 0 -0.5000000000000653 -0.866025403784401 0 0.9659258262891111 -0.2588190451023609 0 0.9659258262891111 -0.2588190451023609 0 -0.2588190451025471 -0.9659258262890613 0 -0.2588190451025471 -0.9659258262890613 0 0.8660254037844973 -0.4999999999998985 0 0.8660254037844973 -0.4999999999998985 0 0 -1 0 0 -1 0 0.7071067811864732 -0.7071067811866219 0 0.7071067811864732 -0.7071067811866219 0 0.2588190451025471 -0.9659258262890613 0 0.2588190451025471 -0.9659258262890613 0 0.4999999999999743 -0.8660254037844535 0 0.4999999999999743 -0.8660254037844535 0 + + + + + + + + + + + + + + +

0 1 2 1 0 3 3 4 1 4 3 5 6 2 7 2 6 0 8 4 5 4 8 9 10 7 11 7 10 6 12 9 8 9 12 13 14 11 15 11 14 10 16 13 12 13 16 17 18 15 19 15 18 14 20 17 16 17 20 21 22 18 19 18 22 23 24 21 20 21 24 25 26 23 22 23 26 27 28 25 24 25 28 29 30 27 26 27 30 31 28 32 29 32 28 33 34 31 30 31 34 35 33 36 32 36 33 37 38 35 34 35 38 39 37 40 36 40 37 41 42 39 38 39 42 43 41 44 40 44 41 45 46 42 47 42 46 43 45 47 44 47 45 46

+
+
+
+ + + + 43.88195393775219 6.659342805574605 0.3207435153034618 50.14313047118674 6.659342805574601 0.04515296412235947 43.88195393775219 6.659342805574605 0.04515296412235925 50.14313047118674 6.659342805574601 0.3207435153034618 43.86143452062263 6.655261239736115 0.3207435153034618 43.88195393775219 6.659342805574605 0.04515296412235925 43.86143452062263 6.655261239736115 0.04515296412235925 43.88195393775219 6.659342805574605 0.3207435153034618 50.14313047118674 6.659342805574601 0.3207435153034618 50.16626363075097 6.657826578190901 0.04515296412235947 50.14313047118674 6.659342805574601 0.04515296412235947 50.16626363075097 6.657826578190901 0.3207435153034618 43.74221309059323 6.536039809706709 0.04515296412235925 43.73813152475472 3.128359607174163 0.04515296412235903 43.73813152475472 6.515520392577111 0.04515296412235925 43.73964775213843 3.105226447609857 0.04515296412235903 43.74395037790404 3.083595687178518 0.04515296412235903 43.74930228759288 6.556923910626212 0.04515296412235925 43.75103957490371 3.062711586259033 0.04515296412235903 43.75905675770041 6.576704019276997 0.04515296412235925 43.76079404501126 3.042931477608272 0.04515296412235903 43.77130959922782 6.59504169251594 0.04515296412235925 43.77304688653869 3.02459380436923 0.04515296412235903 43.78585116265949 6.611623167669842 0.04515296412235925 43.78758844997034 3.00801232921537 0.04515296412235903 43.80243263781338 6.626164731101502 0.04515296412235925 43.80416992512419 2.993470765783732 0.04515296412235903 43.82077031105234 6.638417572628923 0.04515296412235925 43.82250759836319 2.981217924256312 0.04515296412235903 43.84055041970313 6.648172042736457 0.04515296412235925 43.84228770701396 2.971463454148767 0.04515296412235903 43.86143452062263 6.655261239736115 0.04515296412235925 43.86317180793347 2.964374257149116 0.04515296412235903 43.88195393775219 6.659342805574605 0.04515296412235925 43.88480256836478 2.960071631383501 0.04515296412235903 50.14313047118674 6.659342805574601 0.04515296412235947 43.90793572792918 2.958555403999798 0.04515296412235903 50.14313047118665 2.958555403999805 0.04515296412235903 50.166263630751 2.960071631383512 0.04515296412235903 50.16626363075097 6.657826578190901 0.04515296412235947 50.18789439118228 6.653523952425294 0.04515296412235947 50.1878943911823 2.964374257149109 0.04515296412235903 50.20877849210176 6.646434755425636 0.04515296412235947 50.20877849210176 2.971463454148788 0.04515296412235903 50.22855860075256 6.636680285318088 0.04515296412235947 50.22855860075259 2.981217924256329 0.04515296412235903 50.24689627399151 6.624427443790681 0.04515296412235947 50.24689627399157 2.993470765783735 0.04515296412235903 50.26347774914542 6.609885880359011 0.04515296412235947 50.26347774914544 3.008012329215406 0.04515296412235903 50.27801931257708 6.593304405205133 0.04515296412235947 50.27801931257705 3.024593804369262 0.04515296412235903 50.2902721541045 3.042931477608265 0.04515296412235903 50.29027215410449 6.574966731966187 0.04515296412235947 50.30002662421204 6.555186623315345 0.04515296412235947 50.30002662421204 3.062711586259065 0.04515296412235903 50.30711582121172 6.534302522395885 0.04515296412235947 50.30711582121167 3.08359568717851 0.04515296412235903 50.31141844697729 3.105226447609864 0.04515296412235903 50.31141844697731 6.512671761964556 0.04515296412235947 50.31293467436102 3.128359607174145 0.04515296412235903 50.31293467436102 6.489538602400339 0.04515296412235947 43.84055041970313 6.648172042736457 0.3207435153034618 43.84055041970313 6.648172042736457 0.04515296412235925 50.18789439118228 6.653523952425294 0.04515296412235947 50.18789439118228 6.653523952425294 0.3207435153034618 50.30002662421204 6.555186623315345 0.04515296412235947 50.30711582121172 6.534302522395885 0.3207435153034618 50.30711582121172 6.534302522395885 0.04515296412235947 50.30002662421204 6.555186623315345 0.3207435153034618 50.31141844697731 6.512671761964556 0.3207435153034618 50.31141844697731 6.512671761964556 0.04515296412235947 50.31293467436102 6.489538602400339 0.3207435153034618 50.31293467436102 6.489538602400339 0.04515296412235947 50.31293467436102 6.489538602400339 0.04515296412235947 50.31293467436102 3.128359607174145 0.3207435153034614 50.31293467436102 3.128359607174145 0.04515296412235903 50.31293467436102 6.489538602400339 0.3207435153034618 50.31293467436102 3.128359607174145 0.04515296412235903 50.31141844697729 3.105226447609864 0.3207435153034614 50.31141844697729 3.105226447609864 0.04515296412235903 50.31293467436102 3.128359607174145 0.3207435153034614 50.30711582121167 3.08359568717851 0.3207435153034614 50.30711582121167 3.08359568717851 0.04515296412235903 50.30002662421204 3.062711586259065 0.3207435153034614 50.30002662421204 3.062711586259065 0.04515296412235903 50.2902721541045 3.042931477608265 0.3207435153034614 50.2902721541045 3.042931477608265 0.04515296412235903 50.27801931257705 3.024593804369262 0.3207435153034614 50.27801931257705 3.024593804369262 0.04515296412235903 50.26347774914544 3.008012329215406 0.3207435153034614 50.26347774914544 3.008012329215406 0.04515296412235903 50.24689627399157 2.993470765783735 0.04515296412235903 50.24689627399157 2.993470765783735 0.3207435153034614 50.22855860075259 2.981217924256329 0.04515296412235903 50.22855860075259 2.981217924256329 0.3207435153034614 50.20877849210176 2.971463454148788 0.04515296412235903 50.20877849210176 2.971463454148788 0.3207435153034614 50.1878943911823 2.964374257149109 0.04515296412235903 50.1878943911823 2.964374257149109 0.3207435153034614 50.166263630751 2.960071631383512 0.04515296412235903 50.166263630751 2.960071631383512 0.3207435153034614 50.14313047118665 2.958555403999805 0.04515296412235903 50.14313047118665 2.958555403999805 0.3207435153034614 50.14313047118665 2.958555403999805 0.3207435153034614 43.90793572792918 2.958555403999798 0.04515296412235903 50.14313047118665 2.958555403999805 0.04515296412235903 43.90793572792918 2.958555403999798 0.3207435153034614 43.90793572792918 2.958555403999798 0.3207435153034614 43.88480256836478 2.960071631383501 0.04515296412235903 43.90793572792918 2.958555403999798 0.04515296412235903 43.88480256836478 2.960071631383501 0.3207435153034614 43.86317180793347 2.964374257149116 0.04515296412235903 43.86317180793347 2.964374257149116 0.3207435153034614 43.84228770701396 2.971463454148767 0.04515296412235903 43.84228770701396 2.971463454148767 0.3207435153034614 43.82250759836319 2.981217924256312 0.04515296412235903 43.82250759836319 2.981217924256312 0.3207435153034614 43.80416992512419 2.993470765783732 0.04515296412235903 43.80416992512419 2.993470765783732 0.3207435153034614 43.78758844997034 3.00801232921537 0.04515296412235903 43.78758844997034 3.00801232921537 0.3207435153034614 43.77304688653869 3.02459380436923 0.3207435153034614 43.77304688653869 3.02459380436923 0.04515296412235903 43.76079404501126 3.042931477608272 0.3207435153034614 43.76079404501126 3.042931477608272 0.04515296412235903 43.75103957490371 3.062711586259033 0.3207435153034614 43.75103957490371 3.062711586259033 0.04515296412235903 43.74395037790404 3.083595687178518 0.3207435153034614 43.74395037790404 3.083595687178518 0.04515296412235903 43.73964775213843 3.105226447609857 0.3207435153034614 43.73964775213843 3.105226447609857 0.04515296412235903 43.73813152475472 3.128359607174163 0.3207435153034614 43.73813152475472 3.128359607174163 0.04515296412235903 43.73813152475472 6.515520392577111 0.3207435153034618 43.73813152475472 3.128359607174163 0.04515296412235903 43.73813152475472 3.128359607174163 0.3207435153034614 43.73813152475472 6.515520392577111 0.04515296412235925 43.74221309059323 6.536039809706709 0.3207435153034618 43.73813152475472 6.515520392577111 0.04515296412235925 43.73813152475472 6.515520392577111 0.3207435153034618 43.74221309059323 6.536039809706709 0.04515296412235925 43.74930228759288 6.556923910626212 0.3207435153034618 43.74930228759288 6.556923910626212 0.04515296412235925 43.75905675770041 6.576704019276997 0.3207435153034618 43.75905675770041 6.576704019276997 0.04515296412235925 43.77130959922782 6.59504169251594 0.3207435153034618 43.77130959922782 6.59504169251594 0.04515296412235925 43.78585116265949 6.611623167669842 0.3207435153034618 43.78585116265949 6.611623167669842 0.04515296412235925 43.80243263781338 6.626164731101502 0.04515296412235925 43.80243263781338 6.626164731101502 0.3207435153034618 43.82077031105234 6.638417572628923 0.04515296412235925 43.82077031105234 6.638417572628923 0.3207435153034618 50.20877849210176 6.646434755425636 0.04515296412235947 50.20877849210176 6.646434755425636 0.3207435153034618 50.22855860075256 6.636680285318088 0.04515296412235947 50.22855860075256 6.636680285318088 0.3207435153034618 50.24689627399151 6.624427443790681 0.04515296412235947 50.24689627399151 6.624427443790681 0.3207435153034618 50.26347774914542 6.609885880359011 0.04515296412235947 50.26347774914542 6.609885880359011 0.3207435153034618 50.27801931257708 6.593304405205133 0.3207435153034618 50.27801931257708 6.593304405205133 0.04515296412235947 50.29027215410449 6.574966731966187 0.3207435153034618 50.29027215410449 6.574966731966187 0.04515296412235947 + + + + + + + + + + 8.511292549800548e-016 1 6.498920887375498e-031 8.511292549800548e-016 1 6.498920887375498e-031 8.511292549800548e-016 1 6.498920887375498e-031 8.511292549800548e-016 1 6.498920887375498e-031 -0.2588190451025151 0.9659258262890698 0 -0.1950903220161407 0.9807852804032281 0 -0.2588190451025151 0.9659258262890698 0 -0.1950903220161407 0.9807852804032281 0 0.06540312923029935 0.9978589232385934 0 0.1305261922199533 0.9914448613738235 0 0.06540312923029935 0.9978589232385934 0 0.1305261922199533 0.9914448613738235 0 1.203872908821407e-017 1.257059651016985e-016 -1 1.203872908821407e-017 1.257059651016985e-016 -1 1.203872908821407e-017 1.257059651016985e-016 -1 1.203872908821407e-017 1.257059651016985e-016 -1 1.203872908821407e-017 1.257059651016985e-016 -1 1.203872908821407e-017 1.257059651016985e-016 -1 1.203872908821407e-017 1.257059651016985e-016 -1 1.203872908821407e-017 1.257059651016985e-016 -1 1.203872908821407e-017 1.257059651016985e-016 -1 1.203872908821407e-017 1.257059651016985e-016 -1 1.203872908821407e-017 1.257059651016985e-016 -1 1.203872908821407e-017 1.257059651016985e-016 -1 1.203872908821407e-017 1.257059651016985e-016 -1 1.203872908821407e-017 1.257059651016985e-016 -1 1.203872908821407e-017 1.257059651016985e-016 -1 1.203872908821407e-017 1.257059651016985e-016 -1 1.203872908821407e-017 1.257059651016985e-016 -1 1.203872908821407e-017 1.257059651016985e-016 -1 1.203872908821407e-017 1.257059651016985e-016 -1 1.203872908821407e-017 1.257059651016985e-016 -1 1.203872908821407e-017 1.257059651016985e-016 -1 1.203872908821407e-017 1.257059651016985e-016 -1 1.203872908821407e-017 1.257059651016985e-016 -1 1.203872908821407e-017 1.257059651016985e-016 -1 1.203872908821407e-017 1.257059651016985e-016 -1 1.203872908821407e-017 1.257059651016985e-016 -1 1.203872908821407e-017 1.257059651016985e-016 -1 1.203872908821407e-017 1.257059651016985e-016 -1 1.203872908821407e-017 1.257059651016985e-016 -1 1.203872908821407e-017 1.257059651016985e-016 -1 1.203872908821407e-017 1.257059651016985e-016 -1 1.203872908821407e-017 1.257059651016985e-016 -1 1.203872908821407e-017 1.257059651016985e-016 -1 1.203872908821407e-017 1.257059651016985e-016 -1 1.203872908821407e-017 1.257059651016985e-016 -1 1.203872908821407e-017 1.257059651016985e-016 -1 1.203872908821407e-017 1.257059651016985e-016 -1 1.203872908821407e-017 1.257059651016985e-016 -1 1.203872908821407e-017 1.257059651016985e-016 -1 1.203872908821407e-017 1.257059651016985e-016 -1 1.203872908821407e-017 1.257059651016985e-016 -1 1.203872908821407e-017 1.257059651016985e-016 -1 1.203872908821407e-017 1.257059651016985e-016 -1 1.203872908821407e-017 1.257059651016985e-016 -1 1.203872908821407e-017 1.257059651016985e-016 -1 1.203872908821407e-017 1.257059651016985e-016 -1 1.203872908821407e-017 1.257059651016985e-016 -1 1.203872908821407e-017 1.257059651016985e-016 -1 1.203872908821407e-017 1.257059651016985e-016 -1 1.203872908821407e-017 1.257059651016985e-016 -1 -0.3826834323650786 0.9238795325112914 0 -0.3826834323650786 0.9238795325112914 0 0.2588190451024928 0.9659258262890758 0 0.2588190451024928 0.9659258262890758 0 0.9238795325111466 0.382683432365428 0 0.9659258262890319 0.2588190451026563 0 0.9659258262890319 0.2588190451026563 0 0.9238795325111466 0.382683432365428 0 0.9914448613738508 0.1305261922197449 0 0.9914448613738508 0.1305261922197449 0 0.9978589232385635 0.06540312923075399 0 0.9978589232385635 0.06540312923075399 0 1 0 0 1 0 0 1 0 0 1 0 0 0.9978589232385156 -0.06540312923148701 2.148888258984201e-017 0.9914448613737552 -0.1305261922204699 2.330393116351783e-017 0.9914448613737552 -0.1305261922204699 2.330393116351783e-017 0.9978589232385156 -0.06540312923148701 2.148888258984201e-017 0.9659258262891463 -0.2588190451022301 2.66273102819097e-017 0.9659258262891463 -0.2588190451022301 2.66273102819097e-017 0.9238795325113448 -0.3826834323649499 2.949508873891546e-017 0.9238795325113448 -0.3826834323649499 2.949508873891546e-017 0.866025403784477 -0.4999999999999336 3.18581980500125e-017 0.866025403784477 -0.4999999999999336 3.18581980500125e-017 0.7933533402914658 -0.6087614290084201 3.367620475970759e-017 0.7933533402914658 -0.6087614290084201 3.367620475970759e-017 0.7071067811870996 -0.7071067811859956 3.491800226915812e-017 0.7071067811870996 -0.7071067811859956 3.491800226915812e-017 0.6087614290086063 -0.793353340291323 3.556234307869128e-017 0.6087614290086063 -0.793353340291323 3.556234307869128e-017 0.4999999999993188 -0.8660254037848321 3.559820233839578e-017 0.4999999999993188 -0.8660254037848321 3.559820233839578e-017 0.3826834323655604 -0.9238795325110919 3.502496648641106e-017 0.3826834323655604 -0.9238795325110919 3.502496648641106e-017 0.2588190451029568 -0.9659258262889514 3.385244374708522e-017 0.2588190451029568 -0.9659258262889514 3.385244374708522e-017 0.1305261922198004 -0.9914448613738436 3.210069630956563e-017 0.1305261922198004 -0.9914448613738436 3.210069630956563e-017 0.06540312923028356 -0.9978589232385944 3.101660561739596e-017 0.06540312923028356 -0.9978589232385944 3.101660561739596e-017 1.06834484279008e-015 -1 -5.082299223001869e-031 1.06834484279008e-015 -1 -5.082299223001869e-031 1.06834484279008e-015 -1 -5.082299223001869e-031 1.06834484279008e-015 -1 -5.082299223001869e-031 -0.06540312922995278 -0.9978589232386159 0 -0.1305261922199475 -0.9914448613738243 0 -0.06540312922995278 -0.9978589232386159 0 -0.1305261922199475 -0.9914448613738243 0 -0.258819045102376 -0.965925826289107 0 -0.258819045102376 -0.965925826289107 0 -0.3826834323652421 -0.9238795325112236 0 -0.3826834323652421 -0.9238795325112236 0 -0.4999999999998344 -0.8660254037845342 0 -0.4999999999998344 -0.8660254037845342 0 -0.6087614290084823 -0.793353340291418 0 -0.6087614290084823 -0.793353340291418 0 -0.7071067811866187 -0.7071067811864763 0 -0.7071067811866187 -0.7071067811864763 0 -0.7933533402916141 -0.6087614290082266 0 -0.7933533402916141 -0.6087614290082266 0 -0.8660254037845783 -0.4999999999997583 0 -0.8660254037845783 -0.4999999999997583 0 -0.9238795325109536 -0.3826834323658939 0 -0.9238795325109536 -0.3826834323658939 0 -0.9659258262890079 -0.2588190451027462 0 -0.9659258262890079 -0.2588190451027462 0 -0.9914448613738124 -0.130526192220036 0 -0.9914448613738124 -0.130526192220036 0 -0.9978589232385797 -0.0654031292305077 0 -0.9978589232385797 -0.0654031292305077 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -0.9659258262890716 0.2588190451025084 0 -0.9807852804031837 0.1950903220163633 0 -0.9807852804031837 0.1950903220163633 0 -0.9659258262890716 0.2588190451025084 0 -0.9238795325113307 0.382683432364984 0 -0.9238795325113307 0.382683432364984 0 -0.8660254037844439 0.499999999999991 0 -0.8660254037844439 0.499999999999991 0 -0.7933533402912634 0.6087614290086838 0 -0.7933533402912634 0.6087614290086838 0 -0.7071067811865318 0.7071067811865632 0 -0.7071067811865318 0.7071067811865632 0 -0.6087614290087011 0.7933533402912499 0 -0.6087614290087011 0.7933533402912499 0 -0.5000000000000135 0.8660254037844308 0 -0.5000000000000135 0.8660254037844308 0 0.3826834323652957 0.9238795325112014 0 0.3826834323652957 0.9238795325112014 0 0.5000000000000009 0.8660254037844382 0 0.5000000000000009 0.8660254037844382 0 0.608761429008534 0.7933533402913785 0 0.608761429008534 0.7933533402913785 0 0.7071067811863823 0.707106781186713 0 0.7071067811863823 0.707106781186713 0 0.7933533402911205 0.6087614290088703 0 0.7933533402911205 0.6087614290088703 0 0.8660254037845753 0.4999999999997636 0 0.8660254037845753 0.4999999999997636 0 + + + + + + + + + + -0.8126287766250403 0.001458151064450308 -0.9285764902071616 -0.003645377661125661 -0.8126287766250403 -0.003645377661125665 -0.9285764902071616 0.001458151064450308 -0.8206856743251546 0.001458151064450308 -0.8210731079599118 -0.003645377661125665 -0.8206856743251546 -0.003645377661125665 -0.8210731079599118 0.001458151064450308 -0.9185227466979405 0.001458151064450308 -0.9189520577295959 -0.003645377661125661 -0.9185227466979405 -0.003645377661125661 -0.9189520577295959 0.001458151064450308 -0.8100409831591338 0.121037774253828 -0.8099653986065689 0.05793258531804005 -0.8099653986065689 0.1206577850477243 -0.8099934768914524 0.0575041934742566 -0.8100731551463711 0.05710362383663921 -0.8101722645850532 0.1214245168634484 -0.8102044365722909 0.05671688122701912 -0.810352902920378 0.1217908151717962 -0.8103850749076159 0.0563505829186717 -0.8105798073931078 0.1221304017132581 -0.8106119793803461 0.05601099637720797 -0.8108490956048053 0.12243746606796 -0.8108812675920433 0.05570393202250686 -0.8111561599595071 0.1227067542796574 -0.8111883319467441 0.05543464381080985 -0.8114957465009692 0.1229336587523875 -0.8115279184882072 0.05520773933807984 -0.8118620448093171 0.1231142970877122 -0.8118942167965547 0.05502710100275493 -0.8122487874189376 0.1232455785136317 -0.8122809594061753 0.05489581957683547 -0.8126287766250404 0.1233211630661964 -0.8126815290437921 0.05481614132191669 -0.9285764902071617 0.1233211630661963 -0.8131099208875774 0.05478806303703328 -0.9285764902071602 0.05478806303703342 -0.9290048820509445 0.05481614132191688 -0.9290048820509438 0.123293084781313 -0.9294054516885606 0.1232134065263943 -0.9294054516885612 0.05489581957683534 -0.9297921942981807 0.1230821251004747 -0.9297921942981807 0.05502710100275533 -0.9301584926065289 0.1229014867651498 -0.9301584926065293 0.05520773933808017 -0.9304980791479909 0.12267458229242 -0.9304980791479919 0.05543464381080991 -0.9308051435026929 0.1224052940807224 -0.9308051435026934 0.05570393202250751 -0.9310744317143903 0.122098229726021 -0.9310744317143898 0.05601099637720856 -0.9313013361871203 0.05635058291867157 -0.9313013361871202 0.121758643184559 -0.9314819745224451 0.1213923448762101 -0.9314819745224451 0.05671688122701971 -0.9316132559483651 0.1210056022665905 -0.9316132559483643 0.05710362383663908 -0.931692934203283 0.05750419347425673 -0.9316929342032834 0.1206050326289733 -0.931721012488167 0.05793258531803972 -0.931721012488167 0.1201766407851915 -0.8083504250505004 0.001458151064450308 -0.8087588423112614 -0.003645377661125665 -0.8083504250505004 -0.003645377661125665 -0.8087588423112614 0.001458151064450308 -0.8871010261260641 0.001458151064450308 -0.887509443386825 -0.003645377661125661 -0.8871010261260641 -0.003645377661125661 -0.887509443386825 0.001458151064450308 -0.1844649989780748 -0.003645377661125661 -0.1848734162388352 0.001458151064450308 -0.1848734162388352 -0.003645377661125661 -0.1844649989780748 0.001458151064450308 -0.06306821654690635 -0.003645377661125661 -0.06347663380766744 0.001458151064450308 -0.06347663380766744 -0.003645377661125661 -0.06306821654690635 0.001458151064450308 0.05941117461722069 -0.003645377661125661 0.05898186358556559 0.001458151064450308 0.05898186358556559 -0.003645377661125661 0.05941117461722069 0.001458151064450308 0.1201766407851915 -0.003645377661125661 0.05793258531803972 0.0014581510644503 0.05793258531803972 -0.003645377661125669 0.1201766407851915 0.001458151064450308 0.1187460169933381 -0.003645377661125689 0.1183167059616818 0.00145815106445028 0.1183167059616818 -0.003645377661125689 0.1187460169933381 0.00145815106445028 0.2381635410744273 -0.003645377661125695 0.2377551238136656 0.001458151064450275 0.2377551238136656 -0.003645377661125695 0.2381635410744273 0.001458151064450275 0.3535304087755624 -0.003645377661125696 0.3531219915148026 0.001458151064450272 0.3531219915148026 -0.003645377661125696 0.3535304087755624 0.001458151064450272 0.4628517672312365 -0.003645377661125697 0.4624433499704754 0.001458151064450272 0.4624433499704754 -0.003645377661125697 0.4628517672312365 0.001458151064450272 0.5642570976893947 -0.003645377661125694 0.5638486804286331 0.001458151064450275 0.5638486804286331 -0.003645377661125694 0.5642570976893947 0.001458151064450275 0.6560113268299671 -0.003645377661125692 0.655602909569207 0.001458151064450277 0.655602909569207 -0.003645377661125692 0.6560113268299671 0.001458151064450277 0.7365445143547341 0.001458151064450276 0.736136097093973 -0.003645377661125692 0.7365445143547341 -0.003645377661125692 0.736136097093973 0.001458151064450276 0.8044787150972652 0.001458151064450283 0.8040702978365044 -0.003645377661125686 0.8044787150972652 -0.003645377661125686 0.8040702978365044 0.001458151064450283 0.8586515560459136 0.001458151064450287 0.8582431387851521 -0.003645377661125682 0.8586515560459136 -0.003645377661125682 0.8582431387851521 0.001458151064450287 0.898136124873441 0.001458151064450288 0.8977277076126807 -0.00364537766112568 0.898136124873441 -0.00364537766112568 0.8977277076126807 0.001458151064450288 0.9222568296613208 0.001458151064450293 0.9218484124005603 -0.003645377661125676 0.9222568296613208 -0.003645377661125676 0.9218484124005603 0.001458151064450293 0.9306009584615347 0.001458151064450297 0.9301716474298772 -0.003645377661125672 0.9306009584615347 -0.003645377661125672 0.9301716474298772 0.001458151064450297 0.9285764902071602 0.0014581510644503 0.8131099208875774 -0.003645377661125669 0.9285764902071602 -0.003645377661125669 0.8131099208875774 0.0014581510644503 0.8077856793644433 0.0014581510644503 0.8073563683327849 -0.003645377661125669 0.8077856793644433 -0.003645377661125669 0.8073563683327849 0.0014581510644503 0.7863719826795725 0.0014581510644503 0.7859635654188116 -0.003645377661125669 0.7863719826795725 -0.003645377661125669 0.7859635654188116 0.0014581510644503 0.7515276311848284 0.0014581510644503 0.7511192139240673 -0.003645377661125669 0.7515276311848284 -0.003645377661125669 0.7511192139240673 0.0014581510644503 0.7038279276235536 0.0014581510644503 0.7034195103627929 -0.003645377661125669 0.7038279276235536 -0.003645377661125669 0.7034195103627929 0.0014581510644503 0.6440890271500318 0.0014581510644503 0.6436806098892706 -0.003645377661125669 0.6440890271500318 -0.003645377661125669 0.6436806098892706 0.0014581510644503 0.5733330789115873 0.0014581510644503 0.5729246616508272 -0.003645377661125669 0.5733330789115873 -0.003645377661125669 0.5729246616508272 0.0014581510644503 0.4923623195415921 0.0014581510644503 0.4927707368023525 -0.003645377661125669 0.4927707368023525 0.0014581510644503 0.4923623195415921 -0.003645377661125669 0.403372027568609 0.0014581510644503 0.403780444829371 -0.003645377661125669 0.403780444829371 0.0014581510644503 0.403372027568609 -0.003645377661125669 0.3074764343045816 0.0014581510644503 0.3078848515653421 -0.003645377661125669 0.3078848515653421 0.0014581510644503 0.3074764343045816 -0.003645377661125669 0.2063163399331043 0.0014581510644503 0.206724757193865 -0.003645377661125669 0.206724757193865 0.0014581510644503 0.2063163399331043 -0.003645377661125669 0.1016226217163867 0.0014581510644503 0.1020310389771481 -0.003645377661125669 0.1020310389771481 0.0014581510644503 0.1016226217163867 -0.003645377661125669 -0.004834275568581958 0.0014581510644503 -0.004404964536925211 -0.003645377661125669 -0.004404964536925211 0.0014581510644503 -0.004834275568581958 -0.003645377661125669 -0.1206577850477243 0.001458151064450308 -0.05793258531804005 -0.003645377661125669 -0.05793258531804005 0.0014581510644503 -0.1206577850477243 -0.003645377661125665 -0.2767432236118851 0.001458151064450308 -0.2763557899771271 -0.003645377661125665 -0.2763557899771271 0.001458151064450308 -0.2767432236118851 -0.003645377661125665 -0.3754018730088635 0.001458151064450308 -0.3749934557481025 -0.003645377661125665 -0.3749934557481025 0.001458151064450308 -0.3754018730088635 -0.003645377661125665 -0.4676407863444735 0.001458151064450308 -0.4672323690837126 -0.003645377661125665 -0.4672323690837126 0.001458151064450308 -0.4676407863444735 -0.003645377661125665 -0.5518817302372155 0.001458151064450308 -0.5514733129764553 -0.003645377661125665 -0.5514733129764553 0.001458151064450308 -0.5518817302372155 -0.003645377661125665 -0.6266833187814351 0.001458151064450308 -0.6262749015206739 -0.003645377661125665 -0.6262749015206739 0.001458151064450308 -0.6266833187814351 -0.003645377661125665 -0.6903572587974214 0.001458151064450308 -0.6907656760581825 -0.003645377661125665 -0.6903572587974214 -0.003645377661125665 -0.6907656760581825 0.001458151064450308 -0.74262391790657 0.001458151064450308 -0.7430323351673307 -0.003645377661125665 -0.74262391790657 -0.003645377661125665 -0.7430323351673307 0.001458151064450308 -0.7821805818198622 0.001458151064450308 -0.782588999080623 -0.003645377661125665 -0.7821805818198622 -0.003645377661125665 -0.782588999080623 0.001458151064450308 -0.840476373208757 0.001458151064450308 -0.8408847904695179 -0.003645377661125661 -0.840476373208757 -0.003645377661125661 -0.8408847904695179 0.001458151064450308 -0.7794674424557676 0.001458151064450308 -0.7798758597165287 -0.003645377661125661 -0.7794674424557676 -0.003645377661125661 -0.7798758597165287 0.001458151064450308 -0.7051181135869915 0.001458151064450308 -0.7055265308477516 -0.003645377661125661 -0.7051181135869915 -0.003645377661125661 -0.7055265308477516 0.001458151064450308 -0.6187005242327561 0.001458151064450308 -0.6191089414935175 -0.003645377661125661 -0.6187005242327561 -0.003645377661125661 -0.6191089414935175 0.001458151064450308 -0.5216933033061741 -0.003645377661125661 -0.5221017205669348 0.001458151064450308 -0.5221017205669348 -0.003645377661125661 -0.5216933033061741 0.001458151064450308 -0.415756271253232 -0.003645377661125661 -0.4161646885139924 0.001458151064450308 -0.4161646885139924 -0.003645377661125661 -0.415756271253232 0.001458151064450308 -0.3027020400624785 -0.003645377661125661 -0.3031104573232404 0.001458151064450308 -0.3031104573232404 -0.003645377661125661 -0.3027020400624785 0.001458151064450308 + + + + + + + + + + + + + + +

0 0 1 1 2 2 1 1 0 0 3 3 4 4 5 5 6 6 5 5 4 4 7 7 8 8 9 9 10 10 9 9 8 8 11 11 12 12 13 13 14 14 13 13 12 12 15 15 15 15 12 12 16 16 16 16 12 12 17 17 16 16 17 17 18 18 18 18 17 17 19 19 18 18 19 19 20 20 20 20 19 19 21 21 20 20 21 21 22 22 22 22 21 21 23 23 22 22 23 23 24 24 24 24 23 23 25 25 24 24 25 25 26 26 26 26 25 25 27 27 26 26 27 27 28 28 28 28 27 27 29 29 28 28 29 29 30 30 30 30 29 29 31 31 30 30 31 31 32 32 32 32 31 31 33 33 32 32 33 33 34 34 34 34 33 33 35 35 34 34 35 35 36 36 36 36 35 35 37 37 37 37 35 35 38 38 38 38 35 35 39 39 38 38 39 39 40 40 38 38 40 40 41 41 41 41 40 40 42 42 41 41 42 42 43 43 43 43 42 42 44 44 43 43 44 44 45 45 45 45 44 44 46 46 45 45 46 46 47 47 47 47 46 46 48 48 47 47 48 48 49 49 49 49 48 48 50 50 49 49 50 50 51 51 51 51 50 50 52 52 52 52 50 50 53 53 52 52 53 53 54 54 52 52 54 54 55 55 55 55 54 54 56 56 55 55 56 56 57 57 57 57 56 56 58 58 58 58 56 56 59 59 58 58 59 59 60 60 60 60 59 59 61 61 62 62 6 63 63 64 6 63 62 62 4 65 11 66 64 67 9 68 64 67 11 66 65 69 66 70 67 71 68 72 67 71 66 70 69 73 68 74 70 75 71 76 70 75 68 74 67 77 71 78 72 79 73 80 72 79 71 78 70 81 74 82 75 83 76 84 75 83 74 82 77 85 78 86 79 87 80 88 79 87 78 86 81 89 80 90 82 91 83 92 82 91 80 90 79 93 83 94 84 95 85 96 84 95 83 94 82 97 85 98 86 99 87 100 86 99 85 98 84 101 87 102 88 103 89 104 88 103 87 102 86 105 89 106 90 107 91 108 90 107 89 106 88 109 90 110 92 111 91 112 92 111 90 110 93 113 93 114 94 115 92 116 94 115 93 114 95 117 95 118 96 119 94 120 96 119 95 118 97 121 97 122 98 123 96 124 98 123 97 122 99 125 99 126 100 127 98 128 100 127 99 126 101 129 101 130 102 131 100 132 102 131 101 130 103 133 104 134 105 135 106 136 105 135 104 134 107 137 108 138 109 139 110 140 109 139 108 138 111 141 111 142 112 143 109 144 112 143 111 142 113 145 113 146 114 147 112 148 114 147 113 146 115 149 115 150 116 151 114 152 116 151 115 150 117 153 117 154 118 155 116 156 118 155 117 154 119 157 119 158 120 159 118 160 120 159 119 158 121 161 122 162 120 163 121 164 120 163 122 162 123 165 124 166 123 167 122 168 123 167 124 166 125 169 126 170 125 171 124 172 125 171 126 170 127 173 128 174 127 175 126 176 127 175 128 174 129 177 130 178 129 179 128 180 129 179 130 178 131 181 132 182 131 183 130 184 131 183 132 182 133 185 134 186 135 187 136 188 135 187 134 186 137 189 138 190 139 191 140 192 139 191 138 190 141 193 142 194 141 195 138 196 141 195 142 194 143 197 144 198 143 199 142 200 143 199 144 198 145 201 146 202 145 203 144 204 145 203 146 202 147 205 148 206 147 207 146 208 147 207 148 206 149 209 148 210 150 211 149 212 150 211 148 210 151 213 151 214 152 215 150 216 152 215 151 214 153 217 153 218 63 219 152 220 63 219 153 218 62 221 65 222 154 223 64 224 154 223 65 222 155 225 155 226 156 227 154 228 156 227 155 226 157 229 157 230 158 231 156 232 158 231 157 230 159 233 159 234 160 235 158 236 160 235 159 234 161 237 160 238 162 239 163 240 162 239 160 238 161 241 163 242 164 243 165 244 164 243 163 242 162 245 165 246 69 247 66 248 69 247 165 246 164 249

+
+
+
+ + + + 30.11110468898 0.1339882234195979 2.407357688531807 30.10773656538716 0.1287894127682918 2.210507294831021 30.10773656538716 0.1287894127682918 2.407357688531807 30.11110468898 0.1339882234195979 2.210507294831021 30.11324944927784 0.1397995822959413 2.407357688531807 30.11110468898 0.1339882234195979 2.210507294831021 30.11110468898 0.1339882234195979 2.407357688531807 30.11324944927784 0.1397995822959413 2.210507294831021 0.1195943279619485 0.2298517765885322 2.210507294831021 0.1184986753859647 2.439303184052209 2.210507294831021 0.1184986753859647 0.2465682045726894 2.210507294831021 0.1195943279619485 2.456019612036366 2.210507294831021 0.1228625387705549 0.2134213713218518 2.210507294831021 0.1228625387705478 2.472450017303048 2.210507294831021 0.1282473878187176 2.488313271062767 2.210507294831021 0.1282473878187176 0.1975581175621333 2.210507294831021 0.1356567388462722 0.182533439979327 2.210507294831021 0.1356567388462722 2.503337948645571 2.210507294831021 0.1449638158028748 0.1686044149725046 2.210507294831021 0.1449638158028748 2.517266973652395 2.210507294831021 0.1560093720213871 0.1560093720213889 2.210507294831021 0.1560093720213871 2.529862016603511 2.210507294831021 0.1686044149725063 0.1449638158028765 2.210507294831021 0.1686044149725063 2.540907572822023 2.210507294831021 0.1825334399793306 0.1356567388462739 2.210507294831021 0.1825334399793306 2.550214649778626 2.210507294831021 0.1975581175621315 0.1282473878187194 2.210507294831021 0.1975581175621315 2.557624000806181 2.210507294831021 0.2134213713218571 0.1228625387705513 2.210507294831021 0.21342137132185 2.56300884985435 2.210507294831021 0.2298517765885322 2.566277060662953 2.210507294831021 0.2298517765885322 0.1195943279619485 2.210507294831021 0.2465682045726894 0.1184986753859647 2.210507294831021 0.2465682045726894 2.567372713238934 2.210507294831021 0.3460392041832279 0.5491086559751146 2.210507294831021 0.3477764914940522 0.5226027736765069 2.210507294831021 0.3529586279589694 0.4965504143728481 2.210507294831021 0.3614969457863069 0.4713973411548995 2.210507294831021 0.3732453519907679 0.447573930079173 2.210507294831021 0.3880028280849146 0.4254878063142709 2.210507294831021 0.4055168695612395 0.4055168695612395 2.210507294831021 0.4254878063142726 0.3880028280849146 2.210507294831021 0.447573930079173 0.3732453519907644 2.210507294831021 0.4713973411548977 0.3614969457863069 2.210507294831021 0.4965504143728481 0.3529586279589729 2.210507294831021 0.5226027736765104 0.3477764914940558 2.210507294831021 0.5491086559751182 0.3460392041832314 2.210507294831021 30.0860261920037 0.1184986753859683 2.210507294831021 28.98669970978262 0.3460392041831959 2.210507294831021 29.00270410638306 0.3478174866438408 2.210507294831021 29.01792778668387 0.3530655869813781 2.210507294831021 29.03162811879157 0.3615274957018002 2.210507294831021 29.04313678181573 0.3727904293538451 2.210507294831021 29.05189236747371 0.3863049666688863 2.210507294831021 29.05746776635262 0.4014118500799384 2.210507294831021 29.05959100288907 0.4173741452051463 2.210507294831021 0.5491086559751111 2.339832184441677 2.210507294831021 25.56118838034679 2.567372713238937 2.210507294831021 0.5226027736765033 2.338094897130853 2.210507294831021 0.4965504143728481 2.332912760665936 2.210507294831021 0.4713973411548977 2.324374442838602 2.210507294831021 0.447573930079173 2.312626036634145 2.210507294831021 0.4254878063142726 2.297868560539994 2.210507294831021 0.4055168695612395 2.280354519063669 2.210507294831021 0.3880028280849146 2.260383582310636 2.210507294831021 0.3732453519907679 2.238297458545736 2.210507294831021 0.3614969457863069 2.214474047470008 2.210507294831021 0.3529586279589694 2.189320974252061 2.210507294831021 0.3477764914940522 2.163268614948402 2.210507294831021 0.346039204183235 2.136762732649794 2.210507294831021 25.50480608586854 2.33983218444167 2.210507294831021 29.0207414471994 0.4834205400204272 2.210507294831021 30.09912146437194 0.1713469183847511 2.210507294831021 29.03406389556177 0.4743753551861669 2.210507294831021 29.04507585432682 0.4626263227489496 2.210507294831021 29.05324014512329 0.4487465765392891 2.210507294831021 29.05815850270828 0.4334131895122741 2.210507294831021 30.09803909744245 0.1212016043046447 2.210507294831021 30.10330938016302 0.1244567554178957 2.210507294831021 30.10848249331568 0.1633477397435232 2.210507294831021 30.10773656538716 0.1287894127682918 2.210507294831021 30.11110468898 0.1339882234195979 2.210507294831021 30.11162315591949 0.1580084394959354 2.210507294831021 30.11324944927784 0.1397995822959413 2.210507294831021 30.11351516370367 0.1521099485644015 2.210507294831021 30.11406622194742 0.1459400033833784 2.210507294831021 30.10330938016302 0.1244567554178957 2.407357688531807 30.10773656538716 0.1287894127682918 2.210507294831021 30.10330938016302 0.1244567554178957 2.210507294831021 30.10773656538716 0.1287894127682918 2.407357688531807 30.11406622194742 0.1459400033833784 2.407357688531807 30.11324944927784 0.1397995822959413 2.210507294831021 30.11324944927784 0.1397995822959413 2.407357688531807 30.11406622194742 0.1459400033833784 2.210507294831021 30.09912146437194 0.1713469183847511 2.407357688531807 25.56118838034679 2.567372713238937 2.210507294831021 30.09912146437194 0.1713469183847511 2.210507294831021 25.56118838034679 2.567372713238937 2.407357688531807 25.56118838034679 2.567372713238937 2.407357688531807 0.2465682045726894 2.567372713238934 2.210507294831021 25.56118838034679 2.567372713238937 2.210507294831021 0.2465682045726894 2.567372713238934 2.407357688531807 0.2465682045726894 2.567372713238934 2.407357688531807 0.2298517765885322 2.566277060662953 2.210507294831021 0.2465682045726894 2.567372713238934 2.210507294831021 0.2298517765885322 2.566277060662953 2.407357688531807 0.21342137132185 2.56300884985435 2.210507294831021 0.21342137132185 2.56300884985435 2.407357688531807 0.1975581175621315 2.557624000806181 2.210507294831021 0.1975581175621315 2.557624000806181 2.407357688531807 0.1825334399793306 2.550214649778626 2.210507294831021 0.1825334399793306 2.550214649778626 2.407357688531807 0.1686044149725063 2.540907572822023 2.210507294831021 0.1686044149725063 2.540907572822023 2.407357688531807 0.1560093720213871 2.529862016603511 2.210507294831021 0.1560093720213871 2.529862016603511 2.407357688531807 0.1449638158028748 2.517266973652395 2.407357688531807 0.1449638158028748 2.517266973652395 2.210507294831021 0.1356567388462722 2.503337948645571 2.407357688531807 0.1356567388462722 2.503337948645571 2.210507294831021 0.1282473878187176 2.488313271062767 2.407357688531807 0.1282473878187176 2.488313271062767 2.210507294831021 0.1228625387705478 2.472450017303048 2.407357688531807 0.1228625387705478 2.472450017303048 2.210507294831021 0.1195943279619485 2.456019612036366 2.407357688531807 0.1195943279619485 2.456019612036366 2.210507294831021 0.1184986753859647 2.439303184052209 2.407357688531807 0.1184986753859647 2.439303184052209 2.210507294831021 0.1184986753859647 2.439303184052209 2.210507294831021 0.1184986753859647 0.2465682045726894 2.407357688531807 0.1184986753859647 0.2465682045726894 2.210507294831021 0.1184986753859647 2.439303184052209 2.407357688531807 0.1184986753859647 0.2465682045726894 2.210507294831021 0.1195943279619485 0.2298517765885322 2.407357688531807 0.1195943279619485 0.2298517765885322 2.210507294831021 0.1184986753859647 0.2465682045726894 2.407357688531807 0.1228625387705549 0.2134213713218518 2.407357688531807 0.1228625387705549 0.2134213713218518 2.210507294831021 0.1282473878187176 0.1975581175621333 2.407357688531807 0.1282473878187176 0.1975581175621333 2.210507294831021 0.1356567388462722 0.182533439979327 2.407357688531807 0.1356567388462722 0.182533439979327 2.210507294831021 0.1449638158028748 0.1686044149725046 2.407357688531807 0.1449638158028748 0.1686044149725046 2.210507294831021 0.1560093720213871 0.1560093720213889 2.407357688531807 0.1560093720213871 0.1560093720213889 2.210507294831021 0.1686044149725063 0.1449638158028765 2.210507294831021 0.1686044149725063 0.1449638158028765 2.407357688531807 0.1825334399793306 0.1356567388462739 2.210507294831021 0.1825334399793306 0.1356567388462739 2.407357688531807 0.1975581175621315 0.1282473878187194 2.210507294831021 0.1975581175621315 0.1282473878187194 2.407357688531807 0.2134213713218571 0.1228625387705513 2.210507294831021 0.2134213713218571 0.1228625387705513 2.407357688531807 0.2298517765885322 0.1195943279619485 2.210507294831021 0.2298517765885322 0.1195943279619485 2.407357688531807 0.2465682045726894 0.1184986753859647 2.210507294831021 0.2465682045726894 0.1184986753859647 2.407357688531807 0.2465682045726894 0.1184986753859647 2.407357688531807 30.0860261920037 0.1184986753859683 2.210507294831021 0.2465682045726894 0.1184986753859647 2.210507294831021 30.0860261920037 0.1184986753859683 2.407357688531807 30.0860261920037 0.1184986753859683 2.407357688531807 30.09803909744245 0.1212016043046447 2.210507294831021 30.0860261920037 0.1184986753859683 2.210507294831021 30.09803909744245 0.1212016043046447 2.407357688531807 30.09803909744245 0.1212016043046447 2.407357688531807 30.10330938016302 0.1244567554178957 2.210507294831021 30.09803909744245 0.1212016043046447 2.210507294831021 30.10330938016302 0.1244567554178957 2.407357688531807 30.11351516370367 0.1521099485644015 2.407357688531807 30.11406622194742 0.1459400033833784 2.210507294831021 30.11406622194742 0.1459400033833784 2.407357688531807 30.11351516370367 0.1521099485644015 2.210507294831021 30.11162315591949 0.1580084394959354 2.407357688531807 30.11351516370367 0.1521099485644015 2.210507294831021 30.11351516370367 0.1521099485644015 2.407357688531807 30.11162315591949 0.1580084394959354 2.210507294831021 30.10848249331568 0.1633477397435232 2.407357688531807 30.11162315591949 0.1580084394959354 2.210507294831021 30.11162315591949 0.1580084394959354 2.407357688531807 30.10848249331568 0.1633477397435232 2.210507294831021 30.10848249331568 0.1633477397435232 2.407357688531807 30.09912146437194 0.1713469183847511 2.210507294831021 30.10848249331568 0.1633477397435232 2.210507294831021 30.09912146437194 0.1713469183847511 2.407357688531807 + + + + + + + + + + -0.8392617144369261 0.5437276659140966 0 -0.8392617144369261 0.5437276659140966 0 -0.8392617144369261 0.5437276659140966 0 -0.8392617144369261 0.5437276659140966 0 -0.9381474611967006 0.3462359615207312 0 -0.9381474611967006 0.3462359615207312 0 -0.9381474611967006 0.3462359615207312 0 -0.9381474611967006 0.3462359615207312 0 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 -0.6994356363115606 0.7146955930026729 0 -0.6994356363115606 0.7146955930026729 0 -0.6994356363115606 0.7146955930026729 0 -0.6994356363115606 0.7146955930026729 0 -0.9912690949632644 0.1318543945824739 0 -0.9912690949632644 0.1318543945824739 0 -0.9912690949632644 0.1318543945824739 0 -0.9912690949632644 0.1318543945824739 0 -0.4669118737456304 -0.8843038517135073 0 -0.4669118737456304 -0.8843038517135073 0 -0.4669118737456304 -0.8843038517135073 0 -0.4669118737456304 -0.8843038517135073 0 3.508559139078474e-017 -1 0 3.508559139078474e-017 -1 0 3.508559139078474e-017 -1 0 3.508559139078474e-017 -1 0 0.06540312923014653 -0.9978589232386035 0 0.1305261922200657 -0.9914448613738085 0 0.06540312923014653 -0.9978589232386035 0 0.1305261922200657 -0.9914448613738085 0 0.2588190451025326 -0.9659258262890651 0 0.2588190451025326 -0.9659258262890651 0 0.3826834323650984 -0.9238795325112833 0 0.3826834323650984 -0.9238795325112833 0 0.5000000000000157 -0.8660254037844295 0 0.5000000000000157 -0.8660254037844295 0 0.6087614290087283 -0.7933533402912294 0 0.6087614290087283 -0.7933533402912294 0 0.7071067811865515 -0.7071067811865435 0 0.7071067811865515 -0.7071067811865435 0 0.7933533402912371 -0.6087614290087183 0 0.7933533402912371 -0.6087614290087183 0 0.8660254037844378 -0.5000000000000014 0 0.8660254037844378 -0.5000000000000014 0 0.9238795325112877 -0.3826834323650871 0 0.9238795325112877 -0.3826834323650871 0 0.965925826289069 -0.258819045102518 0 0.965925826289069 -0.258819045102518 0 0.9914448613738105 -0.1305261922200504 0 0.9914448613738105 -0.1305261922200504 0 0.9978589232386037 -0.06540312923014092 0 0.9978589232386037 -0.06540312923014092 0 1 0 0 1 0 0 1 0 0 1 0 0 0.9978589232386028 0.06540312923015378 0 0.9914448613738085 0.1305261922200654 0 0.9914448613738085 0.1305261922200654 0 0.9978589232386028 0.06540312923015378 0 0.9659258262890664 0.2588190451025282 0 0.9659258262890664 0.2588190451025282 0 0.9238795325112841 0.3826834323650963 0 0.9238795325112841 0.3826834323650963 0 0.8660254037844283 0.500000000000018 0 0.8660254037844283 0.500000000000018 0 0.7933533402912328 0.6087614290087237 0 0.7933533402912328 0.6087614290087237 0 0.7071067811865434 0.7071067811865516 0 0.7071067811865434 0.7071067811865516 0 0.6087614290087107 0.7933533402912428 0 0.6087614290087107 0.7933533402912428 0 0.5000000000000019 0.8660254037844377 0 0.5000000000000019 0.8660254037844377 0 0.3826834323650855 0.9238795325112886 0 0.3826834323650855 0.9238795325112886 0 0.2588190451025133 0.9659258262890702 0 0.2588190451025133 0.9659258262890702 0 0.1305261922200561 0.9914448613738098 0 0.1305261922200561 0.9914448613738098 0 0.06540312923015844 0.9978589232386027 0 0.06540312923015844 0.9978589232386027 0 -1.083146562226566e-016 1 -1.259049816913602e-017 -1.083146562226566e-016 1 -1.259049816913602e-017 -1.083146562226566e-016 1 -1.259049816913602e-017 -1.083146562226566e-016 1 -1.259049816913602e-017 -0.2195141426946766 0.9756093178916556 0 -0.2195141426946766 0.9756093178916556 0 -0.2195141426946766 0.9756093178916556 0 -0.2195141426946766 0.9756093178916556 0 -0.5254901336654482 0.8507996940645135 0 -0.5254901336654482 0.8507996940645135 0 -0.5254901336654482 0.8507996940645135 0 -0.5254901336654482 0.8507996940645135 0 -0.9960352699715455 -0.08895920960030257 -0 -0.9960352699715455 -0.08895920960030257 -0 -0.9960352699715455 -0.08895920960030257 -0 -0.9960352699715455 -0.08895920960030257 -0 -0.9522134857026214 -0.3054332621802407 -0 -0.9522134857026214 -0.3054332621802407 -0 -0.9522134857026214 -0.3054332621802407 -0 -0.9522134857026214 -0.3054332621802407 -0 -0.8619414285757618 -0.5070078635531948 -0 -0.8619414285757618 -0.5070078635531948 -0 -0.8619414285757618 -0.5070078635531948 -0 -0.8619414285757618 -0.5070078635531948 -0 -0.6496407765509248 -0.7602413178999887 -0 -0.6496407765509248 -0.7602413178999887 -0 -0.6496407765509248 -0.7602413178999887 -0 -0.6496407765509248 -0.7602413178999887 -0 + + + + + + + + + + + + + + +

0 1 2 1 0 3 4 5 6 5 4 7 8 9 10 9 8 11 11 8 12 11 12 13 13 12 14 14 12 15 14 15 16 14 16 17 17 16 18 17 18 19 19 18 20 19 20 21 21 20 22 21 22 23 23 22 24 23 24 25 25 24 26 25 26 27 27 26 28 27 28 29 29 28 30 30 28 31 30 31 32 30 32 33 33 32 34 34 32 35 35 32 36 36 32 37 37 32 38 38 32 39 39 32 40 40 32 41 41 32 42 42 32 43 43 32 44 44 32 45 45 32 46 46 32 47 46 47 48 48 47 49 49 47 50 50 47 51 51 47 52 52 47 53 53 47 54 54 47 55 33 56 57 56 33 58 58 33 59 59 33 60 60 33 61 61 33 62 62 33 63 63 33 64 64 33 65 65 33 66 66 33 67 67 33 68 68 33 69 69 33 34 57 56 70 57 70 71 57 71 72 72 71 73 72 73 74 72 74 75 72 75 76 72 76 55 72 55 47 72 47 77 72 77 78 72 78 79 79 78 80 79 80 81 79 81 82 82 81 83 82 83 84 84 83 85 86 87 88 87 86 89 90 91 92 91 90 93 94 95 96 95 94 97 98 99 100 99 98 101 102 103 104 103 102 105 105 106 103 106 105 107 107 108 106 108 107 109 109 110 108 110 109 111 111 112 110 112 111 113 113 114 112 114 113 115 114 116 117 116 114 115 117 118 119 118 117 116 119 120 121 120 119 118 121 122 123 122 121 120 123 124 125 124 123 122 125 126 127 126 125 124 128 129 130 129 128 131 132 133 134 133 132 135 134 136 137 136 134 133 137 138 139 138 137 136 139 140 141 140 139 138 141 142 143 142 141 140 143 144 145 144 143 142 144 146 145 146 144 147 147 148 146 148 147 149 149 150 148 150 149 151 151 152 150 152 151 153 153 154 152 154 153 155 155 156 154 156 155 157 158 159 160 159 158 161 162 163 164 163 162 165 166 167 168 167 166 169 170 171 172 171 170 173 174 175 176 175 174 177 178 179 180 179 178 181 182 183 184 183 182 185

+
+
+
+ + + + 51.18110236220473 6.474023811682754 1.408731047881116 45.94449345059825 0.7153153851313139 1.408731047881116 45.94449345059825 6.474023811682754 1.408731047881116 51.18110236220473 0.7153153851313139 1.408731047881116 45.94449345059825 0.7153153851313139 1.408731047881116 51.18110236220473 0.7153153851313139 0.8468730150304643 45.94449345059825 0.7153153851313139 0.8468730150304643 51.18110236220473 0.7153153851313139 1.408731047881116 51.18110236220473 6.474023811682754 1.408731047881116 45.94449345059825 6.474023811682754 0.8468730150304621 51.18110236220473 6.474023811682754 0.8468730150304621 45.94449345059825 6.474023811682754 1.408731047881116 51.18110236220473 0.7153153851313139 0.8468730150304643 45.94449345059825 6.474023811682754 0.8468730150304621 45.94449345059825 0.7153153851313139 0.8468730150304643 51.18110236220473 6.474023811682754 0.8468730150304621 + + + + + + + + + + -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 0 1 -3.95196992732243e-016 0 1 -3.95196992732243e-016 0 1 -3.95196992732243e-016 0 1 -3.95196992732243e-016 -0 -1 -1.580787970928972e-015 -0 -1 -1.580787970928972e-015 -0 -1 -1.580787970928972e-015 -0 -1 -1.580787970928972e-015 0 0 1 0 0 1 0 0 1 0 0 1 + + + + + + + + + + -0.9477981918926801 0.1198893298459769 -0.8508239527888565 0.01324658120613544 -0.8508239527888565 0.1198893298459769 -0.9477981918926801 0.01324658120613544 -0.8508239527888565 0.02160606833440687 -0.9477981918926801 0.01120128994828369 -0.8508239527888565 0.01120128994828369 -0.9477981918926801 0.02160606833440687 0.9477981918926801 0.02160606833440667 0.8508239527888565 0.01120128994828346 0.9477981918926801 0.01120128994828346 0.8508239527888565 0.02160606833440667 0.9477981918926801 0.01324658120613544 0.8508239527888565 0.1198893298459769 0.8508239527888565 0.01324658120613544 0.9477981918926801 0.1198893298459769 + + + + + + + + + + + + + + +

0 0 1 1 2 2 1 1 0 0 3 3 4 4 5 5 6 6 5 5 4 4 7 7 8 8 9 9 10 10 9 9 8 8 11 11 12 12 13 13 14 14 13 13 12 12 15 15

+
+
+
+ + + + 45.94449345059825 6.474023811682754 0.8468730150304621 45.94449345059825 0.7153153851313139 1.408731047881116 45.94449345059825 0.7153153851313139 0.8468730150304643 45.94449345059825 6.474023811682754 1.408731047881116 + + + + + + + + + + 1 0 0 1 0 0 1 0 0 1 0 0 + + + + + + + + + + + + + + +

0 1 2 1 0 3

+
+
+
+ + + + 0.1184986753859647 2.804370064010866 2.486097846012126 3.763089190289442 4.829011243202418 2.486097846012126 0.1184986753859647 7.126416329097724 2.486097846012126 5.577594676008829 3.993671778922126 2.486097846012126 5.848211101779548 3.881578785166932 2.486097846012126 6.138618298056045 3.843345952459808 2.486097846012126 25.61991398185795 2.804370064010866 2.486097846012126 3.730473949157663 4.854037797942242 2.486097846012126 3.705447394417853 4.886653039073993 2.486097846012126 3.68971504441712 4.924634291813741 2.486097846012126 3.684349032809131 4.965393196554297 2.486097846012126 3.801070443029168 4.8132788932017 2.486097846012126 3.841829347769725 4.807912881593675 2.486097846012126 3.882588252510281 4.8132788932017 2.486097846012126 3.920569505250036 4.829011243202418 2.486097846012126 3.953184746381801 4.854037797942242 2.486097846012126 3.978211301121611 4.886653039073993 2.486097846012126 3.993943651122343 4.924634291813741 2.486097846012126 3.999309662730347 4.965393196554297 2.486097846012126 5.345211082945141 4.171985981443397 2.486097846012126 5.166896880423835 4.404369574507031 2.486097846012126 5.054803886668701 4.674986000277832 2.486097846012126 5.016571053961556 4.965393196554279 2.486097846012126 6.429025494332535 3.881578785166932 2.486097846012126 6.699641920103375 3.993671778922126 2.486097846012126 6.93202551316692 4.171985981443397 2.486097846012126 7.110339715688212 4.404369574507031 2.486097846012126 7.22243270944341 4.674986000277832 2.486097846012126 7.260665542150491 4.965393196554279 2.486097846012126 6.138618298056045 6.087440440648775 2.486097846012126 51.06260368681876 7.126416329097724 2.486097846012127 5.848211101779548 6.04920760794162 2.486097846012126 5.577594676008829 5.937114614186443 2.486097846012126 3.763089190289442 5.101775149906183 2.486097846012126 3.730473949157663 5.076748595166359 2.486097846012126 3.705447394417853 5.04413335403463 2.486097846012126 3.68971504441712 5.006152101294854 2.486097846012126 3.801070443029168 5.11750749990693 2.486097846012126 3.841829347769725 5.122873511514927 2.486097846012126 3.882588252510281 5.11750749990693 2.486097846012126 3.920569505250036 5.101775149906183 2.486097846012126 3.953184746381801 5.076748595166359 2.486097846012126 3.978211301121611 5.04413335403463 2.486097846012126 3.993943651122343 5.006152101294854 2.486097846012126 5.345211082945141 5.758800411665172 2.486097846012126 5.166896880423835 5.52641681860152 2.486097846012126 5.054803886668701 5.255800392830723 2.486097846012126 6.429025494332535 6.04920760794162 2.486097846012126 6.699641920103375 5.937114614186443 2.486097846012126 6.93202551316692 5.758800411665172 2.486097846012126 7.110339715688212 5.52641681860152 2.486097846012126 7.22243270944341 5.255800392830723 2.486097846012126 30.70679771243117 0.1184986753859665 2.486097846012126 51.06260368681876 0.1184986753859647 2.486097846012126 + + + + + + + + + + -1.114631815844137e-017 -8.602164972986113e-017 1 -1.114631815844137e-017 -8.602164972986113e-017 1 -1.114631815844137e-017 -8.602164972986113e-017 1 -1.114631815844137e-017 -8.602164972986113e-017 1 -1.114631815844137e-017 -8.602164972986113e-017 1 -1.114631815844137e-017 -8.602164972986113e-017 1 -1.114631815844137e-017 -8.602164972986113e-017 1 -1.114631815844137e-017 -8.602164972986113e-017 1 -1.114631815844137e-017 -8.602164972986113e-017 1 -1.114631815844137e-017 -8.602164972986113e-017 1 -1.114631815844137e-017 -8.602164972986113e-017 1 -1.114631815844137e-017 -8.602164972986113e-017 1 -1.114631815844137e-017 -8.602164972986113e-017 1 -1.114631815844137e-017 -8.602164972986113e-017 1 -1.114631815844137e-017 -8.602164972986113e-017 1 -1.114631815844137e-017 -8.602164972986113e-017 1 -1.114631815844137e-017 -8.602164972986113e-017 1 -1.114631815844137e-017 -8.602164972986113e-017 1 -1.114631815844137e-017 -8.602164972986113e-017 1 -1.114631815844137e-017 -8.602164972986113e-017 1 -1.114631815844137e-017 -8.602164972986113e-017 1 -1.114631815844137e-017 -8.602164972986113e-017 1 -1.114631815844137e-017 -8.602164972986113e-017 1 -1.114631815844137e-017 -8.602164972986113e-017 1 -1.114631815844137e-017 -8.602164972986113e-017 1 -1.114631815844137e-017 -8.602164972986113e-017 1 -1.114631815844137e-017 -8.602164972986113e-017 1 -1.114631815844137e-017 -8.602164972986113e-017 1 -1.114631815844137e-017 -8.602164972986113e-017 1 -1.114631815844137e-017 -8.602164972986113e-017 1 -1.114631815844137e-017 -8.602164972986113e-017 1 -1.114631815844137e-017 -8.602164972986113e-017 1 -1.114631815844137e-017 -8.602164972986113e-017 1 -1.114631815844137e-017 -8.602164972986113e-017 1 -1.114631815844137e-017 -8.602164972986113e-017 1 -1.114631815844137e-017 -8.602164972986113e-017 1 -1.114631815844137e-017 -8.602164972986113e-017 1 -1.114631815844137e-017 -8.602164972986113e-017 1 -1.114631815844137e-017 -8.602164972986113e-017 1 -1.114631815844137e-017 -8.602164972986113e-017 1 -1.114631815844137e-017 -8.602164972986113e-017 1 -1.114631815844137e-017 -8.602164972986113e-017 1 -1.114631815844137e-017 -8.602164972986113e-017 1 -1.114631815844137e-017 -8.602164972986113e-017 1 -1.114631815844137e-017 -8.602164972986113e-017 1 -1.114631815844137e-017 -8.602164972986113e-017 1 -1.114631815844137e-017 -8.602164972986113e-017 1 -1.114631815844137e-017 -8.602164972986113e-017 1 -1.114631815844137e-017 -8.602164972986113e-017 1 -1.114631815844137e-017 -8.602164972986113e-017 1 -1.114631815844137e-017 -8.602164972986113e-017 1 -1.114631815844137e-017 -8.602164972986113e-017 1 -1.114631815844137e-017 -8.602164972986113e-017 1 -1.114631815844137e-017 -8.602164972986113e-017 1 + + + + + + + + + + + + + + +

0 1 2 1 0 3 3 0 4 4 0 5 5 0 6 2 1 7 2 7 8 2 8 9 2 9 10 1 3 11 11 3 12 12 3 13 13 3 14 14 3 15 15 3 16 16 3 17 17 3 18 18 3 19 18 19 20 18 20 21 18 21 22 5 6 23 23 6 24 24 6 25 25 6 26 26 6 27 27 6 28 2 29 30 29 2 31 31 2 32 32 2 33 33 2 34 34 2 35 35 2 36 36 2 10 32 33 37 32 37 38 32 38 39 32 39 40 32 40 41 32 41 42 32 42 43 32 43 18 32 18 44 44 18 45 45 18 46 46 18 22 30 29 47 30 47 48 30 48 49 30 49 50 30 50 51 30 51 28 30 28 6 30 6 52 30 52 53

+
+
+
+ + + + 43.8785667103903 6.693733902121489 0.2420033578231468 43.9050725926889 6.695471189432313 0.2420033578231468 + + + + + + + + + + + + + +

1 0

+
+
+
+ + + + 43.70200314089702 6.49240173764043 0.2420033578231468 43.70374042820784 6.518907619939037 0.2420033578231468 + + + + + + + + + + + + + +

1 0

+
+
+
+ + + + 0 0 3.076649027114485 0 0 2.407357688531807 + + + + + + + + + + + + + +

1 0

+
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + ID7 + + + + + ID8 + + + + + + + + + + + + + + + + + 0.05882352941176471 0.05882352941176471 0.05882352941176471 1 + + + + + + + + + + + 1 1 1 1 + + + + + + + + + + + 0.05882352941176471 0.05882352941176471 0.05882352941176471 1 + + + 1 + + + + + + + + + + + 0 0 0 1 + + + 1 + + + + + + + + + + + 0 0 0 1 + + + + + + + + + + + 0.2431372549019608 0.3568627450980392 0.4352941176470588 1 + + + + + + + + + + + 0.1254901960784314 0.2117647058823529 0.2274509803921569 1 + + + + + + + + + + + 0.2156862745098039 0.3568627450980392 0.3843137254901961 1 + + + + + + + + + + + 0.2431372549019608 0.3568627450980392 0.4352941176470588 1 + + + 1 + + + + + + + + + r200_entire/texture0.jpg + + + + + +
diff --git a/ros-realsense-nav/turtlebot/robot_description/meshes/sensors/r200_entire/texture0.jpg b/ros-realsense-nav/turtlebot/robot_description/meshes/sensors/r200_entire/texture0.jpg new file mode 100644 index 0000000000000000000000000000000000000000..8956fcfcb83eab1bac701cc67b9452489010b95e GIT binary patch literal 2508 zcmZXU4K&p09><^mf6VNd8O@9FGNTx;c_}nwD(x_ul*Yp67he`TfrGeV*TW&Uscw zR>lFz*N5u^AQ*rct-#7F5bBj0osb3~paTFf1u)=f-3;si+dvrb2RslAf&c?}0WSDL zyS@Y-+71JFYTX}rgFvk_{!d_K2CVXkN!}#}F&b?iwDK4n1SC8jPr#E11d2w=sOH(bD&JK=i*RFMRV6&Z_*=z)H|9ixW29U9kc2*Q*0bnwOB10>kAPzu(p}pq6 zfdGuc{7+5WgJ2SXAsB^4{bvJ2o;BYP5aqEqyQrcOrrduzcf(>=-~;mCP&Efsq@kb;78gtt4T?Q^WhpDm0I1FsLQ=*6L{7| zs!~@mCI}ZCSuTUh-MG;L!INjsmxew4I+l?KbB|X~4E5gr!AG8f#&skMkT{Y+hH>tfi8duouJ?JxjpjhJoXJ;wc9eNe(fTcOg69f#)Q4P!p=j7t== zOVkfpZ%pLNrxR`-IC$;@N^hK%k>4By!2z|afqtn`r*7J&|>pK zLA^E}@2AfUI;-!|C1@7nb69Cj>pS)aMM~}J7Fz2fD`_hLXRjgjoH#$=!~euo`i`D2 z^OUg;*%qJUd`SHsq7O3*>7(5SqkiN>eI*%nA`&hwqr=^K@0=mP}mvsbyc6 zgZeIr+Zw`amkz1UdYy)?(pV;q8K@akC3Yu@vt6rnCZy6bFdi~O32McjsVh|c@f-Ty zsS$eM-17cahrUatccN!mpB`zj|7a_U=;53&_{w3DH$975eMMpKo%vjV1fJb^j1DJu zBzXEOQ_A4{QWO_%dvZuVTm>p@2N7D)VSF}Ub#h!34^w|x(CrUOl2!?QO+H4GGu{9z zD@^z$)zG9KixF3L`nFruwF@&SdZ@)hfAWbGs<`RFgN;6VWio{r}w z%2bA58dtFWOcJR0?8}0@#svuZsy${f+jx(pOcbo%Ru0RQhOtPm<}SbYNndmM4xVLD zU~D79Nc(Lm!;&&@rM~q2b`JJ;zv1vZ!_I=l$DyXBVZh0rq|gMn?WYqD;?L=JJ{M_fF3EI%Lx0SHFSi~sy`Ds?KTjY$SlS{&KNz|8mg}VrF{U(;9%x@5_c6bSd zz9Ff-K1G+6~JZ)?T=}2wh50R<&MWy?Xuf?)xE4U?2ZFZ%0x$ zQm5|m`SBI&`R`@M3#A2SJJa)?JY=}PhzSV6z8?Ls_IDbT!CC&|M#g7XmB-iJ*)B>R zsYz2ZD0qdliwDud*WFE;eUt^rp%#ZoZ(#eISPlB8yh@hvhIB}{wRSg2FA02tvUR0S zpVQ~GGbbIUDCk+=?@*?cs;*nbk*Mcny}oGZ1>=w8E3 z-YvhU)_dtuxNB9trt1zo5*yda)DZQZE8W9=d~?EO#l}+#zcHP*=ikLu(Ch40hqP?%(Ip6|x8|%-tf5 zP`Z#r@k2|-J4jx*g?A;ZW>MCzSqDJXkxiGcn#7ipSlFbZvtjp0@#B7b&$7Ck3wC34 zPZuQ;ZXiSaN(5`Op@t(`RWBa8dqvX|40MxU%*HP|`>!jtvKw+{6CE`Zv5yI^GK@0) z>F0+Q7hFm|rXs#f6Uto1yJOA-k2*b<-VS6n29f@VKAO)Qy9`l@?=vheE1)v0Ag~^z x+N_~YNm!J&8N2gK*(wUKZvAn + + + + Google SketchUp 8.0.4811 + + 2015-05-31T08:41:34Z + 2015-05-31T08:41:34Z + + Z_UP + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + 0.1184986753859656 7.755517072645532 2.24409448818898 51.06260368681876 7.755517072645532 2.165354330708662 0.1184986753859656 7.755517072645532 2.165354330708662 51.06260368681876 7.755517072645532 2.24409448818898 0.1184986753859656 7.755517072645532 2.24409448818898 0.1184986753859656 2.804370064010866 2.165354330708662 0.1184986753859656 2.804370064010866 2.24409448818898 0.1184986753859656 7.755517072645532 2.165354330708662 51.06260368681876 7.755517072645532 2.165354330708662 51.06260368681876 0.1184986753859656 2.24409448818898 51.06260368681876 0.1184986753859656 2.165354330708662 51.06260368681876 7.755517072645532 2.24409448818898 25.61991398185795 2.804370064010866 2.24409448818898 0.1184986753859656 2.804370064010866 2.165354330708662 25.61991398185795 2.804370064010866 2.165354330708662 0.1184986753859656 2.804370064010866 2.24409448818898 51.06260368681876 0.1184986753859656 2.24409448818898 30.70679771243117 0.1184986753859656 2.165354330708662 51.06260368681876 0.1184986753859656 2.165354330708662 30.70679771243117 0.1184986753859656 2.24409448818898 30.70679771243117 0.1184986753859656 2.24409448818898 25.61991398185795 2.804370064010866 2.165354330708662 30.70679771243117 0.1184986753859656 2.165354330708662 25.61991398185795 2.804370064010866 2.24409448818898 + + + + + + + + + + 0 1 0 0 1 0 0 1 0 0 1 0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 -1.741429659934826e-017 -1 -0 -1.741429659934826e-017 -1 -0 -1.741429659934826e-017 -1 -0 -1.741429659934826e-017 -1 -0 -1.363521329027796e-018 -1 1.38790518535184e-045 -1.363521329027796e-018 -1 1.38790518535184e-045 -1.363521329027796e-018 -1 1.38790518535184e-045 -1.363521329027796e-018 -1 1.38790518535184e-045 -0.4669118737456303 -0.8843038517135072 -0 -0.4669118737456303 -0.8843038517135072 -0 -0.4669118737456303 -0.8843038517135072 -0 -0.4669118737456303 -0.8843038517135072 -0 + + + + + + + + + + + + + + +

0 1 2 1 0 3 4 5 6 5 4 7 8 9 10 9 8 11 12 13 14 13 12 15 16 17 18 17 16 19 20 21 22 21 20 23

+
+
+
+ + + + 0.1184986753859656 2.43930318405221 1.968503937007876 0.1184986753859656 0.2465682045726894 2.165354330708662 0.1184986753859656 0.2465682045726894 1.968503937007876 0.1184986753859656 2.43930318405221 2.165354330708662 0.1184986753859656 0.2465682045726894 1.968503937007876 0.119594327961949 0.2298517765885317 2.165354330708662 0.119594327961949 0.2298517765885317 1.968503937007876 0.1184986753859656 0.2465682045726894 2.165354330708662 0.2465682045726913 0.1184986753859656 1.968503937007876 0.3477764914940549 0.5226027736765067 1.968503937007876 0.3460392041832313 0.5491086559751139 1.968503937007876 0.352958627958972 0.4965504143728474 1.968503937007876 0.361496945786306 0.4713973411548998 1.968503937007876 0.3732453519907644 0.4475739300791728 1.968503937007876 0.3880028280849136 0.4254878063142707 1.968503937007876 0.4055168695612388 0.4055168695612393 1.968503937007876 0.4254878063142707 0.3880028280849154 1.968503937007876 0.4475739300791731 0.3732453519907652 1.968503937007876 0.4713973411549005 0.3614969457863064 1.968503937007876 0.4965504143728469 0.3529586279589738 1.968503937007876 0.5226027736765072 0.3477764914940557 1.968503937007876 0.5491086559751147 0.346039204183232 1.968503937007876 30.0860261920037 0.1184986753859688 1.968503937007876 28.98669970978262 0.3460392041831966 1.968503937007876 29.00270410638306 0.3478174866438403 1.968503937007876 29.01792778668387 0.3530655869813785 1.968503937007876 29.03162811879157 0.3615274957018001 1.968503937007876 29.04313678181573 0.3727904293538459 1.968503937007876 29.05189236747371 0.386304966668887 1.968503937007876 29.05746776635262 0.4014118500799385 1.968503937007876 29.05959100288907 0.4173741452051467 1.968503937007876 0.119594327961949 0.2298517765885317 1.968503937007876 0.1184986753859656 2.43930318405221 1.968503937007876 0.1184986753859656 0.2465682045726894 1.968503937007876 0.1195943279619488 2.456019612036368 1.968503937007876 0.1228625387705512 2.472450017303047 1.968503937007876 0.1228625387705518 0.2134213713218521 1.968503937007876 0.1282473878187184 2.488313271062767 1.968503937007876 0.1282473878187189 0.1975581175621329 1.968503937007876 0.1356567388462739 2.503337948645572 1.968503937007876 0.1356567388462747 0.1825334399793274 1.968503937007876 0.1449638158028762 2.517266973652394 1.968503937007876 0.1449638158028776 0.1686044149725052 1.968503937007876 0.1560093720213884 2.529862016603511 1.968503937007876 0.1560093720213896 0.1560093720213882 1.968503937007876 0.1686044149725052 2.540907572822023 1.968503937007876 0.1686044149725068 0.1449638158028763 1.968503937007876 0.1825334399793273 2.550214649778626 1.968503937007876 0.1825334399793289 0.1356567388462739 1.968503937007876 0.1975581175621327 2.557624000806182 1.968503937007876 0.197558117562134 0.1282473878187185 1.968503937007876 0.213421371321852 2.563008849854349 1.968503937007876 0.2134213713218537 0.1228625387705514 1.968503937007876 0.2298517765885315 2.566277060662952 1.968503937007876 0.2298517765885331 0.1195943279619491 1.968503937007876 0.2465682045726894 2.567372713238935 1.968503937007876 0.3460392041832319 2.136762732649793 1.968503937007876 0.3477764914940558 2.163268614948401 1.968503937007876 0.3529586279589722 2.189320974252061 1.968503937007876 0.3614969457863068 2.214474047470008 1.968503937007876 0.3732453519907648 2.238297458545735 1.968503937007876 0.3880028280849145 2.260383582310638 1.968503937007876 0.4055168695612396 2.280354519063669 1.968503937007876 0.4254878063142705 2.297868560539994 1.968503937007876 0.4475739300791732 2.312626036634144 1.968503937007876 0.4713973411548998 2.324374442838602 1.968503937007876 0.4965504143728471 2.332912760665936 1.968503937007876 0.5226027736765068 2.338094897130853 1.968503937007876 0.5491086559751146 2.339832184441677 1.968503937007876 25.56118838034679 2.567372713238936 1.968503937007876 25.50480608586854 2.339832184441669 1.968503937007876 29.0207414471994 0.4834205400204281 1.968503937007876 30.09912146437194 0.1713469183847506 1.968503937007876 29.03406389556177 0.4743753551861666 1.968503937007876 29.04507585432682 0.4626263227489491 1.968503937007876 29.05324014512329 0.4487465765392888 1.968503937007876 29.05815850270828 0.4334131895122746 1.968503937007876 30.09803909744245 0.1212016043046447 1.968503937007876 30.10330938016302 0.1244567554178949 1.968503937007876 30.10848249331568 0.1633477397435226 1.968503937007876 30.10773656538716 0.1287894127682915 1.968503937007876 30.11110468898 0.1339882234195986 1.968503937007876 30.11162315591949 0.1580084394959358 1.968503937007876 30.11324944927784 0.1397995822959414 1.968503937007876 30.11351516370367 0.1521099485644012 1.968503937007876 30.11406622194742 0.145940003383379 1.968503937007876 0.1195943279619488 2.456019612036368 1.968503937007876 0.1184986753859656 2.43930318405221 2.165354330708662 0.1184986753859656 2.43930318405221 1.968503937007876 0.1195943279619488 2.456019612036368 2.165354330708662 0.1228625387705518 0.2134213713218521 2.165354330708662 0.1228625387705518 0.2134213713218521 1.968503937007876 30.09912146437194 0.1713469183847506 2.165354330708662 25.56118838034679 2.567372713238936 1.968503937007876 30.09912146437194 0.1713469183847506 1.968503937007876 25.56118838034679 2.567372713238936 2.165354330708662 25.56118838034679 2.567372713238936 2.165354330708662 0.2465682045726894 2.567372713238935 1.968503937007876 25.56118838034679 2.567372713238936 1.968503937007876 0.2465682045726894 2.567372713238935 2.165354330708662 0.2465682045726894 2.567372713238935 2.165354330708662 0.2298517765885315 2.566277060662952 1.968503937007876 0.2465682045726894 2.567372713238935 1.968503937007876 0.2298517765885315 2.566277060662952 2.165354330708662 0.213421371321852 2.563008849854349 1.968503937007876 0.213421371321852 2.563008849854349 2.165354330708662 0.1975581175621327 2.557624000806182 1.968503937007876 0.1975581175621327 2.557624000806182 2.165354330708662 0.1825334399793273 2.550214649778626 1.968503937007876 0.1825334399793273 2.550214649778626 2.165354330708662 0.1686044149725052 2.540907572822023 1.968503937007876 0.1686044149725052 2.540907572822023 2.165354330708662 0.1560093720213884 2.529862016603511 1.968503937007876 0.1560093720213884 2.529862016603511 2.165354330708662 0.1449638158028762 2.517266973652394 2.165354330708662 0.1449638158028762 2.517266973652394 1.968503937007876 0.1356567388462739 2.503337948645572 2.165354330708662 0.1356567388462739 2.503337948645572 1.968503937007876 0.1282473878187184 2.488313271062767 2.165354330708662 0.1282473878187184 2.488313271062767 1.968503937007876 0.1228625387705512 2.472450017303047 2.165354330708662 0.1228625387705512 2.472450017303047 1.968503937007876 0.1282473878187189 0.1975581175621329 2.165354330708662 0.1282473878187189 0.1975581175621329 1.968503937007876 0.1356567388462747 0.1825334399793274 2.165354330708662 0.1356567388462747 0.1825334399793274 1.968503937007876 0.1449638158028776 0.1686044149725052 2.165354330708662 0.1449638158028776 0.1686044149725052 1.968503937007876 0.1560093720213896 0.1560093720213882 2.165354330708662 0.1560093720213896 0.1560093720213882 1.968503937007876 0.1686044149725068 0.1449638158028763 1.968503937007876 0.1686044149725068 0.1449638158028763 2.165354330708662 0.1825334399793289 0.1356567388462739 1.968503937007876 0.1825334399793289 0.1356567388462739 2.165354330708662 0.197558117562134 0.1282473878187185 1.968503937007876 0.197558117562134 0.1282473878187185 2.165354330708662 0.2134213713218537 0.1228625387705514 1.968503937007876 0.2134213713218537 0.1228625387705514 2.165354330708662 0.2298517765885331 0.1195943279619491 1.968503937007876 0.2298517765885331 0.1195943279619491 2.165354330708662 0.2465682045726913 0.1184986753859656 1.968503937007876 0.2465682045726913 0.1184986753859656 2.165354330708662 0.2465682045726913 0.1184986753859656 2.165354330708662 30.0860261920037 0.1184986753859688 1.968503937007876 0.2465682045726913 0.1184986753859656 1.968503937007876 30.0860261920037 0.1184986753859688 2.165354330708662 30.0860261920037 0.1184986753859688 2.165354330708662 30.09803909744245 0.1212016043046447 1.968503937007876 30.0860261920037 0.1184986753859688 1.968503937007876 30.09803909744245 0.1212016043046447 2.165354330708662 30.09803909744245 0.1212016043046447 2.165354330708662 30.10330938016302 0.1244567554178949 1.968503937007876 30.09803909744245 0.1212016043046447 1.968503937007876 30.10330938016302 0.1244567554178949 2.165354330708662 30.10330938016302 0.1244567554178949 2.165354330708662 30.10773656538716 0.1287894127682915 1.968503937007876 30.10330938016302 0.1244567554178949 1.968503937007876 30.10773656538716 0.1287894127682915 2.165354330708662 30.11110468898 0.1339882234195986 2.165354330708662 30.10773656538716 0.1287894127682915 1.968503937007876 30.10773656538716 0.1287894127682915 2.165354330708662 30.11110468898 0.1339882234195986 1.968503937007876 30.11324944927784 0.1397995822959414 2.165354330708662 30.11110468898 0.1339882234195986 1.968503937007876 30.11110468898 0.1339882234195986 2.165354330708662 30.11324944927784 0.1397995822959414 1.968503937007876 30.11406622194742 0.145940003383379 2.165354330708662 30.11324944927784 0.1397995822959414 1.968503937007876 30.11324944927784 0.1397995822959414 2.165354330708662 30.11406622194742 0.145940003383379 1.968503937007876 30.11351516370367 0.1521099485644012 2.165354330708662 30.11406622194742 0.145940003383379 1.968503937007876 30.11406622194742 0.145940003383379 2.165354330708662 30.11351516370367 0.1521099485644012 1.968503937007876 30.11162315591949 0.1580084394959358 2.165354330708662 30.11351516370367 0.1521099485644012 1.968503937007876 30.11351516370367 0.1521099485644012 2.165354330708662 30.11162315591949 0.1580084394959358 1.968503937007876 30.10848249331568 0.1633477397435226 2.165354330708662 30.11162315591949 0.1580084394959358 1.968503937007876 30.11162315591949 0.1580084394959358 2.165354330708662 30.10848249331568 0.1633477397435226 1.968503937007876 30.10848249331568 0.1633477397435226 2.165354330708662 30.09912146437194 0.1713469183847506 1.968503937007876 30.10848249331568 0.1633477397435226 1.968503937007876 30.09912146437194 0.1713469183847506 2.165354330708662 + + + + + + + + + + 1 0 0 1 0 0 1 0 0 1 0 0 0.9978589232386028 0.06540312923015378 0 0.9914448613738085 0.1305261922200654 0 0.9914448613738085 0.1305261922200654 0 0.9978589232386028 0.06540312923015378 0 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 2.656193772464903e-032 5.126105274048653e-031 1 0.9914448613738105 -0.1305261922200504 0 0.9978589232386037 -0.06540312923014092 -0 0.9978589232386037 -0.06540312923014092 -0 0.9914448613738105 -0.1305261922200504 0 0.9659258262890664 0.2588190451025282 0 0.9659258262890664 0.2588190451025282 0 -0.4669118737456304 -0.8843038517135073 0 -0.4669118737456304 -0.8843038517135073 0 -0.4669118737456304 -0.8843038517135073 0 -0.4669118737456304 -0.8843038517135073 0 3.508559139078474e-017 -1 -0 3.508559139078474e-017 -1 -0 3.508559139078474e-017 -1 -0 3.508559139078474e-017 -1 -0 0.06540312923014653 -0.9978589232386035 -0 0.1305261922200657 -0.9914448613738085 0 0.06540312923014653 -0.9978589232386035 -0 0.1305261922200657 -0.9914448613738085 0 0.2588190451025326 -0.9659258262890651 0 0.2588190451025326 -0.9659258262890651 0 0.3826834323650984 -0.9238795325112833 0 0.3826834323650984 -0.9238795325112833 0 0.5000000000000157 -0.8660254037844295 0 0.5000000000000157 -0.8660254037844295 0 0.6087614290087283 -0.7933533402912294 0 0.6087614290087283 -0.7933533402912294 0 0.7071067811865515 -0.7071067811865435 0 0.7071067811865515 -0.7071067811865435 0 0.7933533402912371 -0.6087614290087183 0 0.7933533402912371 -0.6087614290087183 0 0.8660254037844378 -0.5000000000000014 0 0.8660254037844378 -0.5000000000000014 0 0.9238795325112877 -0.3826834323650871 0 0.9238795325112877 -0.3826834323650871 0 0.965925826289069 -0.258819045102518 0 0.965925826289069 -0.258819045102518 0 0.9238795325112841 0.3826834323650963 0 0.9238795325112841 0.3826834323650963 0 0.8660254037844283 0.500000000000018 0 0.8660254037844283 0.500000000000018 0 0.7933533402912328 0.6087614290087237 0 0.7933533402912328 0.6087614290087237 0 0.7071067811865434 0.7071067811865516 0 0.7071067811865434 0.7071067811865516 0 0.6087614290087107 0.7933533402912428 0 0.6087614290087107 0.7933533402912428 0 0.5000000000000019 0.8660254037844377 0 0.5000000000000019 0.8660254037844377 0 0.3826834323650855 0.9238795325112886 0 0.3826834323650855 0.9238795325112886 0 0.2588190451025133 0.9659258262890702 0 0.2588190451025133 0.9659258262890702 0 0.1305261922200561 0.9914448613738098 0 0.1305261922200561 0.9914448613738098 0 0.06540312923015844 0.9978589232386027 0 0.06540312923015844 0.9978589232386027 0 -1.083146562226566e-016 1 -1.259049816913602e-017 -1.083146562226566e-016 1 -1.259049816913602e-017 -1.083146562226566e-016 1 -1.259049816913602e-017 -1.083146562226566e-016 1 -1.259049816913602e-017 -0.2195141426946766 0.9756093178916556 -0 -0.2195141426946766 0.9756093178916556 -0 -0.2195141426946766 0.9756093178916556 -0 -0.2195141426946766 0.9756093178916556 -0 -0.5254901336654482 0.8507996940645135 -0 -0.5254901336654482 0.8507996940645135 -0 -0.5254901336654482 0.8507996940645135 -0 -0.5254901336654482 0.8507996940645135 -0 -0.6994356363115606 0.7146955930026729 -0 -0.6994356363115606 0.7146955930026729 -0 -0.6994356363115606 0.7146955930026729 -0 -0.6994356363115606 0.7146955930026729 -0 -0.8392617144369261 0.5437276659140966 -0 -0.8392617144369261 0.5437276659140966 -0 -0.8392617144369261 0.5437276659140966 -0 -0.8392617144369261 0.5437276659140966 -0 -0.9381474611967006 0.3462359615207312 -0 -0.9381474611967006 0.3462359615207312 -0 -0.9381474611967006 0.3462359615207312 -0 -0.9381474611967006 0.3462359615207312 -0 -0.9912690949632644 0.1318543945824739 -0 -0.9912690949632644 0.1318543945824739 -0 -0.9912690949632644 0.1318543945824739 -0 -0.9912690949632644 0.1318543945824739 -0 -0.9960352699715455 -0.08895920960030257 -0 -0.9960352699715455 -0.08895920960030257 -0 -0.9960352699715455 -0.08895920960030257 -0 -0.9960352699715455 -0.08895920960030257 -0 -0.9522134857026214 -0.3054332621802407 -0 -0.9522134857026214 -0.3054332621802407 -0 -0.9522134857026214 -0.3054332621802407 -0 -0.9522134857026214 -0.3054332621802407 -0 -0.8619414285757618 -0.5070078635531948 -0 -0.8619414285757618 -0.5070078635531948 -0 -0.8619414285757618 -0.5070078635531948 -0 -0.8619414285757618 -0.5070078635531948 -0 -0.6496407765509248 -0.7602413178999887 -0 -0.6496407765509248 -0.7602413178999887 -0 -0.6496407765509248 -0.7602413178999887 -0 -0.6496407765509248 -0.7602413178999887 -0 + + + + + + + + + + + + + + +

0 1 2 1 0 3 4 5 6 5 4 7 8 9 10 9 8 11 11 8 12 12 8 13 13 8 14 14 8 15 15 8 16 16 8 17 17 8 18 18 8 19 19 8 20 20 8 21 21 8 22 21 22 23 23 22 24 24 22 25 25 22 26 26 22 27 27 22 28 28 22 29 29 22 30 31 32 33 32 31 34 34 31 35 35 31 36 35 36 37 37 36 38 37 38 39 39 38 40 39 40 41 41 40 42 41 42 43 43 42 44 43 44 45 45 44 46 45 46 47 47 46 48 47 48 49 49 48 50 49 50 51 51 50 52 51 52 53 53 52 54 53 54 55 55 54 8 55 8 56 55 56 57 55 57 58 55 58 59 55 59 60 55 60 61 55 61 62 55 62 63 55 63 64 55 64 65 55 65 66 55 66 67 55 67 68 55 68 69 56 8 10 69 68 70 69 70 71 69 71 72 72 71 73 72 73 74 72 74 75 72 75 76 72 76 30 72 30 22 72 22 77 72 77 78 72 78 79 79 78 80 79 80 81 79 81 82 82 81 83 82 83 84 84 83 85 86 87 88 87 86 89 6 90 91 90 6 5 92 93 94 93 92 95 96 97 98 97 96 99 100 101 102 101 100 103 103 104 101 104 103 105 105 106 104 106 105 107 107 108 106 108 107 109 109 110 108 110 109 111 111 112 110 112 111 113 112 114 115 114 112 113 115 116 117 116 115 114 117 118 119 118 117 116 119 120 121 120 119 118 121 89 86 89 121 120 91 122 123 122 91 90 123 124 125 124 123 122 125 126 127 126 125 124 127 128 129 128 127 126 128 130 129 130 128 131 131 132 130 132 131 133 133 134 132 134 133 135 135 136 134 136 135 137 137 138 136 138 137 139 139 140 138 140 139 141 142 143 144 143 142 145 146 147 148 147 146 149 150 151 152 151 150 153 154 155 156 155 154 157 158 159 160 159 158 161 162 163 164 163 162 165 166 167 168 167 166 169 170 171 172 171 170 173 174 175 176 175 174 177 178 179 180 179 178 181 182 183 184 183 182 185

+
+
+
+ + + + 29.00270410638306 0.3478174866438403 1.968503937007876 29.01792778668387 0.3530655869813785 1.062992125984253 29.00270410638306 0.3478174866438403 1.062992125984253 29.01792778668387 0.3530655869813785 1.968503937007876 28.98669970978262 0.3460392041831966 1.968503937007876 29.00270410638306 0.3478174866438403 1.110223024625157e-015 28.98669970978262 0.3460392041831966 1.110223024625157e-015 29.03162811879157 0.3615274957018001 1.062992125984253 29.03162811879157 0.3615274957018001 1.968503937007876 43.19998259988454 2.339832184441669 1.062992125984254 29.0207414471994 0.4834205400204281 1.062992125984253 25.50480608586854 2.339832184441669 1.062992125984253 29.03406389556177 0.4743753551861666 1.062992125984253 29.04507585432682 0.4626263227489491 1.062992125984253 29.05324014512329 0.4487465765392888 1.062992125984253 29.05815850270828 0.4334131895122746 1.062992125984253 29.05959100288907 0.4173741452051467 1.062992125984253 43.1999825998845 0.3478174866438403 1.062992125984253 43.22648848218315 0.3495547739546886 1.062992125984253 43.22648848218314 2.338094897130838 1.062992125984254 43.25254084148678 2.332912760665932 1.062992125984254 43.25254084148678 0.3547369104195798 1.062992125984253 43.27769391470476 2.324374442838592 1.062992125984254 43.27769391470472 0.3632752282469342 1.062992125984253 43.30151732578045 0.3750236344513948 1.062992125984253 43.30151732578047 2.312626036634134 1.062992125984254 43.32360344954538 0.3897811105455223 1.062992125984253 43.32360344954538 2.297868560539985 1.062992125984254 43.34357438629841 2.280354519063661 1.062992125984254 43.34357438629839 0.4072951520218343 1.062992125984253 43.36108842777473 0.4272660887748755 1.062992125984253 43.36108842777473 2.260383582310626 1.062992125984254 43.37584590386888 2.238297458545732 1.062992125984254 43.37584590386889 0.4493522125397943 1.062992125984253 43.38759431007334 2.214474047469995 1.062992125984254 43.38759431007329 0.4731756236155132 1.062992125984253 43.39613262790066 0.4983286968334623 1.062992125984253 43.39613262790067 2.189320974252053 1.062992125984254 43.40131476436558 0.5243810561371171 1.062992125984253 43.40131476436559 2.163268614948387 1.062992125984254 43.4030520516764 0.5508869384357514 1.062992125984253 43.4030520516764 2.136762732649783 1.062992125984254 29.01792778668387 0.3530655869813785 1.062992125984253 29.00270410638306 0.3478174866438403 1.062992125984253 29.03162811879157 0.3615274957018001 1.062992125984253 29.04313678181573 0.3727904293538459 1.062992125984253 29.05189236747371 0.386304966668887 1.062992125984253 29.05746776635262 0.4014118500799385 1.062992125984253 0.5491086559751147 0.346039204183232 1.968503937007876 28.98669970978262 0.3460392041831966 1.110223024625157e-015 0.5491086559751147 0.346039204183232 1.110223024625157e-015 28.98669970978262 0.3460392041831966 1.968503937007876 29.00270410638306 0.3478174866438403 1.110223024625157e-015 43.1999825998845 0.3478174866438403 0.157480314960631 50.14425631911605 0.3478174866438403 1.110223024625157e-015 29.00270410638306 0.3478174866438403 1.062992125984253 43.1999825998845 0.3478174866438403 1.062992125984253 50.14425631911605 0.3478174866438403 0.157480314960631 29.04313678181573 0.3727904293538459 1.062992125984253 29.04313678181573 0.3727904293538459 1.968503937007876 43.4030520516764 2.136762732649783 1.062992125984254 43.4030520516764 0.5508869384357514 0.157480314960631 43.4030520516764 0.5508869384357514 1.062992125984253 43.4030520516764 2.136762732649783 0.1574803149606311 43.4030520516764 0.5508869384357514 1.062992125984253 43.40131476436558 0.5243810561371171 0.157480314960631 43.40131476436558 0.5243810561371171 1.062992125984253 43.4030520516764 0.5508869384357514 0.157480314960631 43.39613262790066 0.4983286968334623 0.157480314960631 43.39613262790066 0.4983286968334623 1.062992125984253 43.38759431007329 0.4731756236155132 0.157480314960631 43.38759431007329 0.4731756236155132 1.062992125984253 43.37584590386889 0.4493522125397943 0.157480314960631 43.37584590386889 0.4493522125397943 1.062992125984253 43.36108842777473 0.4272660887748755 0.157480314960631 43.36108842777473 0.4272660887748755 1.062992125984253 43.34357438629839 0.4072951520218343 0.157480314960631 43.34357438629839 0.4072951520218343 1.062992125984253 43.32360344954538 0.3897811105455223 1.062992125984253 43.32360344954538 0.3897811105455223 0.157480314960631 43.30151732578045 0.3750236344513948 1.062992125984253 43.30151732578045 0.3750236344513948 0.157480314960631 43.27769391470472 0.3632752282469342 1.062992125984253 43.27769391470472 0.3632752282469342 0.157480314960631 43.25254084148678 0.3547369104195798 1.062992125984253 43.25254084148678 0.3547369104195798 0.157480314960631 43.22648848218315 0.3495547739546886 1.062992125984253 43.22648848218315 0.3495547739546886 0.157480314960631 43.1999825998845 0.3478174866438403 1.062992125984253 43.1999825998845 0.3478174866438403 0.157480314960631 29.05189236747371 0.386304966668887 1.968503937007876 29.05189236747371 0.386304966668887 1.062992125984253 29.05746776635262 0.4014118500799385 1.968503937007876 29.05746776635262 0.4014118500799385 1.062992125984253 29.05959100288907 0.4173741452051467 1.968503937007876 29.05959100288907 0.4173741452051467 1.062992125984253 29.05815850270828 0.4334131895122746 1.968503937007876 29.05815850270828 0.4334131895122746 1.062992125984253 29.05324014512329 0.4487465765392888 1.968503937007876 29.05324014512329 0.4487465765392888 1.062992125984253 29.04507585432682 0.4626263227489491 1.968503937007876 29.04507585432682 0.4626263227489491 1.062992125984253 29.03406389556177 0.4743753551861666 1.968503937007876 29.03406389556177 0.4743753551861666 1.062992125984253 29.0207414471994 0.4834205400204281 1.062992125984253 29.0207414471994 0.4834205400204281 1.968503937007876 29.0207414471994 0.4834205400204281 1.968503937007876 25.50480608586854 2.339832184441669 1.062992125984253 29.0207414471994 0.4834205400204281 1.062992125984253 25.50480608586854 2.339832184441669 1.968503937007876 50.14425631911605 2.339832184441669 0.157480314960631 25.50480608586854 2.339832184441669 1.110223024625157e-015 50.14425631911605 2.339832184441669 1.110223024625157e-015 43.19998259988454 2.339832184441669 0.1574803149606311 25.50480608586854 2.339832184441669 1.062992125984253 43.19998259988454 2.339832184441669 1.062992125984254 43.22648848218314 2.338094897130838 1.062992125984254 43.19998259988454 2.339832184441669 0.1574803149606311 43.22648848218314 2.338094897130838 0.1574803149606311 43.19998259988454 2.339832184441669 1.062992125984254 43.25254084148678 2.332912760665932 1.062992125984254 43.25254084148678 2.332912760665932 0.1574803149606311 43.27769391470476 2.324374442838592 1.062992125984254 43.27769391470476 2.324374442838592 0.1574803149606311 43.30151732578047 2.312626036634134 1.062992125984254 43.30151732578047 2.312626036634134 0.1574803149606311 43.32360344954538 2.297868560539985 1.062992125984254 43.32360344954538 2.297868560539985 0.1574803149606311 43.34357438629841 2.280354519063661 1.062992125984254 43.34357438629841 2.280354519063661 0.1574803149606311 43.36108842777473 2.260383582310626 0.1574803149606311 43.36108842777473 2.260383582310626 1.062992125984254 43.37584590386888 2.238297458545732 0.1574803149606311 43.37584590386888 2.238297458545732 1.062992125984254 43.38759431007334 2.214474047469995 0.1574803149606311 43.38759431007334 2.214474047469995 1.062992125984254 43.39613262790067 2.189320974252053 0.1574803149606311 43.39613262790067 2.189320974252053 1.062992125984254 43.40131476436559 2.163268614948387 0.1574803149606311 43.40131476436559 2.163268614948387 1.062992125984254 43.4030520516764 2.136762732649783 0.1574803149606311 43.4030520516764 2.136762732649783 1.062992125984254 0.5226027736765072 0.3477764914940557 1.968503937007876 0.5491086559751147 0.346039204183232 1.110223024625157e-015 0.5226027736765072 0.3477764914940557 1.110223024625157e-015 0.5491086559751147 0.346039204183232 1.968503937007876 50.14425631911605 2.339832184441669 0.157480314960631 43.22648848218314 2.338094897130838 0.1574803149606311 43.19998259988454 2.339832184441669 0.1574803149606311 43.25254084148678 2.332912760665932 0.1574803149606311 43.27769391470476 2.324374442838592 0.1574803149606311 43.30151732578047 2.312626036634134 0.1574803149606311 43.32360344954538 2.297868560539985 0.1574803149606311 43.34357438629841 2.280354519063661 0.1574803149606311 43.36108842777473 2.260383582310626 0.1574803149606311 43.37584590386888 2.238297458545732 0.1574803149606311 43.38759431007334 2.214474047469995 0.1574803149606311 43.39613262790067 2.189320974252053 0.1574803149606311 43.40131476436559 2.163268614948387 0.1574803149606311 43.4030520516764 2.136762732649783 0.1574803149606311 43.4030520516764 0.5508869384357514 0.157480314960631 43.22648848218315 0.3495547739546886 0.157480314960631 50.14425631911605 0.3478174866438403 0.157480314960631 43.1999825998845 0.3478174866438403 0.157480314960631 43.25254084148678 0.3547369104195798 0.157480314960631 43.27769391470472 0.3632752282469342 0.157480314960631 43.30151732578045 0.3750236344513948 0.157480314960631 43.32360344954538 0.3897811105455223 0.157480314960631 43.34357438629839 0.4072951520218343 0.157480314960631 43.36108842777473 0.4272660887748755 0.157480314960631 43.37584590386889 0.4493522125397943 0.157480314960631 43.38759431007329 0.4731756236155132 0.157480314960631 43.39613262790066 0.4983286968334623 0.157480314960631 43.40131476436558 0.5243810561371171 0.157480314960631 50.17076220141468 2.338094897130827 0.157480314960631 50.17076220141466 0.3495547739546495 0.157480314960631 50.19681456071831 0.35473691041958 0.157480314960631 50.19681456071832 2.332912760665919 0.157480314960631 50.22196763393623 0.3632752282469015 0.157480314960631 50.22196763393626 2.324374442838587 0.157480314960631 50.24579104501201 0.3750236344513794 0.157480314960631 50.24579104501199 2.312626036634129 0.157480314960631 50.26787716877689 2.297868560539985 0.157480314960631 50.26787716877686 0.3897811105455421 0.157480314960631 50.28784810552991 0.407295152021843 0.157480314960631 50.28784810552993 2.280354519063654 0.157480314960631 50.30536214700624 0.4272660887748815 0.157480314960631 50.30536214700626 2.260383582310614 0.157480314960631 50.32011962310041 0.4493522125397739 0.157480314960631 50.32011962310039 2.238297458545719 0.157480314960631 50.33186802930484 2.214474047469999 0.157480314960631 50.33186802930485 0.4731756236154915 0.157480314960631 50.34040634713219 2.189320974252057 0.157480314960631 50.3404063471322 0.498328696833425 0.157480314960631 50.34558848359709 2.163268614948385 0.157480314960631 50.34558848359711 0.5243810561371139 0.157480314960631 50.3473257709079 2.136762732649773 0.157480314960631 50.3473257709079 0.5508869384357039 0.157480314960631 50.14425631911605 0.3478174866438403 0.157480314960631 50.17076220141466 0.3495547739546495 1.110223024625157e-015 50.14425631911605 0.3478174866438403 1.110223024625157e-015 50.17076220141466 0.3495547739546495 0.157480314960631 25.50480608586854 2.339832184441669 1.062992125984253 0.5491086559751146 2.339832184441677 1.110223024625157e-015 25.50480608586854 2.339832184441669 1.110223024625157e-015 0.5491086559751146 2.339832184441677 1.968503937007876 25.50480608586854 2.339832184441669 1.968503937007876 50.17076220141468 2.338094897130827 0.157480314960631 50.14425631911605 2.339832184441669 1.110223024625157e-015 50.17076220141468 2.338094897130827 1.110223024625157e-015 50.14425631911605 2.339832184441669 0.157480314960631 0.4965504143728469 0.3529586279589738 1.968503937007876 0.4965504143728469 0.3529586279589738 1.110223024625157e-015 50.19681456071832 2.332912760665919 0.157480314960631 50.19681456071832 2.332912760665919 1.110223024625157e-015 50.22196763393626 2.324374442838587 0.157480314960631 50.22196763393626 2.324374442838587 1.110223024625157e-015 50.24579104501199 2.312626036634129 0.157480314960631 50.24579104501199 2.312626036634129 1.110223024625157e-015 50.26787716877689 2.297868560539985 0.157480314960631 50.26787716877689 2.297868560539985 1.110223024625157e-015 50.28784810552993 2.280354519063654 0.157480314960631 50.28784810552993 2.280354519063654 1.110223024625157e-015 50.30536214700626 2.260383582310614 1.110223024625157e-015 50.30536214700626 2.260383582310614 0.157480314960631 50.32011962310039 2.238297458545719 1.110223024625157e-015 50.32011962310039 2.238297458545719 0.157480314960631 50.33186802930484 2.214474047469999 1.110223024625157e-015 50.33186802930484 2.214474047469999 0.157480314960631 50.34040634713219 2.189320974252057 1.110223024625157e-015 50.34040634713219 2.189320974252057 0.157480314960631 50.34558848359709 2.163268614948385 1.110223024625157e-015 50.34558848359709 2.163268614948385 0.157480314960631 50.3473257709079 2.136762732649773 1.110223024625157e-015 50.3473257709079 2.136762732649773 0.157480314960631 50.3473257709079 2.136762732649773 0.157480314960631 50.3473257709079 0.5508869384357039 1.110223024625157e-015 50.3473257709079 0.5508869384357039 0.157480314960631 50.3473257709079 2.136762732649773 1.110223024625157e-015 50.3473257709079 0.5508869384357039 0.157480314960631 50.34558848359711 0.5243810561371139 1.110223024625157e-015 50.34558848359711 0.5243810561371139 0.157480314960631 50.3473257709079 0.5508869384357039 1.110223024625157e-015 50.3404063471322 0.498328696833425 1.110223024625157e-015 50.3404063471322 0.498328696833425 0.157480314960631 50.33186802930485 0.4731756236154915 1.110223024625157e-015 50.33186802930485 0.4731756236154915 0.157480314960631 50.32011962310041 0.4493522125397739 1.110223024625157e-015 50.32011962310041 0.4493522125397739 0.157480314960631 50.30536214700624 0.4272660887748815 1.110223024625157e-015 50.30536214700624 0.4272660887748815 0.157480314960631 50.28784810552991 0.407295152021843 1.110223024625157e-015 50.28784810552991 0.407295152021843 0.157480314960631 50.26787716877686 0.3897811105455421 0.157480314960631 50.26787716877686 0.3897811105455421 1.110223024625157e-015 50.24579104501201 0.3750236344513794 0.157480314960631 50.24579104501201 0.3750236344513794 1.110223024625157e-015 50.22196763393623 0.3632752282469015 0.157480314960631 50.22196763393623 0.3632752282469015 1.110223024625157e-015 50.19681456071831 0.35473691041958 0.157480314960631 50.19681456071831 0.35473691041958 1.110223024625157e-015 0.5491086559751146 2.339832184441677 1.968503937007876 0.5226027736765068 2.338094897130853 1.110223024625157e-015 0.5491086559751146 2.339832184441677 1.110223024625157e-015 0.5226027736765068 2.338094897130853 1.968503937007876 0.4713973411549005 0.3614969457863064 1.968503937007876 0.4713973411549005 0.3614969457863064 1.110223024625157e-015 0.4965504143728471 2.332912760665936 1.110223024625157e-015 0.4965504143728471 2.332912760665936 1.968503937007876 0.4475739300791731 0.3732453519907652 1.968503937007876 0.4475739300791731 0.3732453519907652 1.110223024625157e-015 0.4713973411548998 2.324374442838602 1.110223024625157e-015 0.4713973411548998 2.324374442838602 1.968503937007876 0.4254878063142707 0.3880028280849154 1.968503937007876 0.4254878063142707 0.3880028280849154 1.110223024625157e-015 0.4475739300791732 2.312626036634144 1.110223024625157e-015 0.4475739300791732 2.312626036634144 1.968503937007876 0.4055168695612388 0.4055168695612393 1.968503937007876 0.4055168695612388 0.4055168695612393 1.110223024625157e-015 0.4254878063142705 2.297868560539994 1.110223024625157e-015 0.4254878063142705 2.297868560539994 1.968503937007876 0.3880028280849136 0.4254878063142707 1.110223024625157e-015 0.3880028280849136 0.4254878063142707 1.968503937007876 0.4055168695612396 2.280354519063669 1.110223024625157e-015 0.4055168695612396 2.280354519063669 1.968503937007876 0.3732453519907644 0.4475739300791728 1.110223024625157e-015 0.3732453519907644 0.4475739300791728 1.968503937007876 0.3880028280849145 2.260383582310638 1.968503937007876 0.3880028280849145 2.260383582310638 1.110223024625157e-015 0.361496945786306 0.4713973411548998 1.110223024625157e-015 0.361496945786306 0.4713973411548998 1.968503937007876 0.3732453519907648 2.238297458545735 1.968503937007876 0.3732453519907648 2.238297458545735 1.110223024625157e-015 0.352958627958972 0.4965504143728474 1.110223024625157e-015 0.352958627958972 0.4965504143728474 1.968503937007876 0.3614969457863068 2.214474047470008 1.968503937007876 0.3614969457863068 2.214474047470008 1.110223024625157e-015 0.3477764914940549 0.5226027736765067 1.110223024625157e-015 0.3477764914940549 0.5226027736765067 1.968503937007876 0.3529586279589722 2.189320974252061 1.968503937007876 0.3529586279589722 2.189320974252061 1.110223024625157e-015 0.3460392041832313 0.5491086559751139 1.110223024625157e-015 0.3460392041832313 0.5491086559751139 1.968503937007876 0.3477764914940558 2.163268614948401 1.968503937007876 0.3477764914940558 2.163268614948401 1.110223024625157e-015 0.3460392041832319 2.136762732649793 1.110223024625157e-015 0.3460392041832313 0.5491086559751139 1.968503937007876 0.3460392041832313 0.5491086559751139 1.110223024625157e-015 0.3460392041832319 2.136762732649793 1.968503937007876 0.3460392041832319 2.136762732649793 1.968503937007876 0.3460392041832319 2.136762732649793 1.110223024625157e-015 + + + + + + + + + + -0.2195141426946883 0.9756093178916528 -2.251662460960872e-031 -0.4283200860438445 0.9036270823140448 -2.039446246926806e-031 -0.1832544872618059 0.983065507938516 -2.276641252136103e-031 -0.4283200860438445 0.9036270823140448 -2.039446246926806e-031 -0.1104325181011955 0.9938836244479679 -2.317022766077274e-031 -0.1104325181011955 0.9938836244479679 -2.317022766077274e-031 -0.1104325181011955 0.9938836244479679 -2.317022766077274e-031 -0.6162319912743373 0.7875646849180484 -1.727743062721139e-031 -0.6162319912743373 0.7875646849180484 -1.727743062721139e-031 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 -9.643711856883541e-019 3.816831467890428e-017 -1 1.247349874666141e-015 1 -2.354039508393784e-031 1.247349874666141e-015 1 -2.354039508393784e-031 1.247349874666141e-015 1 -2.354039508393784e-031 1.247349874666141e-015 1 -2.354039508393784e-031 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0.7740832592965722 0.6330838077828211 -1.331758214899901e-031 -0.7740832592965722 0.6330838077828211 -1.331758214899901e-031 -1 -5.063450264559819e-035 9.643711856883543e-019 -1 -5.063450264559819e-035 9.643711856883543e-019 -1 -5.063450264559819e-035 9.643711856883543e-019 -1 -5.063450264559819e-035 9.643711856883543e-019 -0.9978589232386242 0.06540312922982872 3.458633610382481e-018 -0.9914448613738267 0.1305261922199271 5.938085634997029e-018 -0.9914448613738267 0.1305261922199271 5.938085634997029e-018 -0.9978589232386242 0.06540312922982872 3.458633610382481e-018 -0.9659258262888851 0.2588190451032043 1.081019779277784e-017 -0.9659258262888851 0.2588190451032043 1.081019779277784e-017 -0.9238795325113519 0.3826834323649326 1.549734446910911e-017 -0.9238795325113519 0.3826834323649326 1.549734446910911e-017 -0.8660254037849143 0.4999999999991764 1.9919327284905e-017 -0.8660254037849143 0.4999999999991764 1.9919327284905e-017 -0.7933533402911954 0.6087614290087726 2.400048488823272e-017 -0.7933533402911954 0.6087614290087726 2.400048488823272e-017 -0.7071067811865249 0.7071067811865701 2.767098754089725e-017 -0.7071067811865249 0.7071067811865701 2.767098754089725e-017 -0.60876142900828 0.7933533402915732 3.086803192490265e-017 -0.60876142900828 0.7933533402915732 3.086803192490265e-017 -0.4999999999994493 0.8660254037847566 3.353691572442538e-017 -0.4999999999994493 0.8660254037847566 3.353691572442538e-017 -0.3826834323655326 0.9238795325111033 3.563197359769641e-017 -0.3826834323655326 0.9238795325111033 3.563197359769641e-017 -0.2588190451025693 0.9659258262890552 3.711735852368559e-017 -0.2588190451025693 0.9659258262890552 3.711735852368559e-017 -0.1305261922200869 0.9914448613738056 3.796765515445271e-017 -0.1305261922200869 0.9914448613738056 3.796765515445271e-017 -0.06540312923095472 0.9978589232385504 3.814966628060576e-017 -0.06540312923095472 0.9978589232385504 3.814966628060576e-017 -0.8941736899130333 0.4477202388404067 -8.708083845489539e-032 -0.8941736899130333 0.4477202388404067 -8.708083845489539e-032 -0.9706451080888319 0.2405162658599619 -3.673793332284476e-032 -0.9706451080888319 0.2405162658599619 -3.673793332284476e-032 -0.9997671337217909 0.02157958131462663 1.539709831518109e-032 -0.9997671337217909 0.02157958131462663 1.539709831518109e-032 -0.9801191546728204 -0.1984097846464127 6.67810384924031e-032 -0.9801191546728204 -0.1984097846464127 6.67810384924031e-032 -0.9126596261640011 -0.4087204506385578 1.149073085081814e-031 -0.9126596261640011 -0.4087204506385578 1.149073085081814e-031 -0.8006793160253677 -0.5990931754653439 1.574282432564735e-031 -0.8006793160253677 -0.5990931754653439 1.574282432564735e-031 -0.6496407765509797 -0.7602413178999415 1.9226961353246e-031 -0.6496407765509797 -0.7602413178999415 1.9226961353246e-031 -0.5617119664874528 -0.8273328633052111 2.062622892710896e-031 -0.5617119664874528 -0.8273328633052111 2.062622892710896e-031 -0.4669118737456301 -0.8843038517135073 2.177318097629222e-031 -0.4669118737456301 -0.8843038517135073 2.177318097629222e-031 -0.4669118737456301 -0.8843038517135073 2.177318097629222e-031 -0.4669118737456301 -0.8843038517135073 2.177318097629222e-031 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.1305261922200457 -0.9914448613738112 -3.771590375694363e-017 -0.06540312923042768 -0.9978589232385848 -3.802352049403922e-017 -0.1305261922200457 -0.9914448613738112 -3.771590375694363e-017 -0.06540312923042768 -0.9978589232385848 -3.802352049403922e-017 -0.2588190451023318 -0.9659258262891188 -3.661816326487966e-017 -0.2588190451023318 -0.9659258262891188 -3.661816326487966e-017 -0.3826834323651677 -0.9238795325112544 -3.489387584687525e-017 -0.3826834323651677 -0.9238795325112544 -3.489387584687525e-017 -0.5000000000000009 -0.8660254037844382 -3.25725445387254e-017 -0.5000000000000009 -0.8660254037844382 -3.25725445387254e-017 -0.6087614290086468 -0.7933533402912919 -2.969388796270346e-017 -0.6087614290086468 -0.7933533402912919 -2.969388796270346e-017 -0.707106781186616 -0.707106781186479 -2.630716073093143e-017 -0.707106781186616 -0.707106781186479 -2.630716073093143e-017 -0.7933533402912433 -0.6087614290087099 -2.247031068533741e-017 -0.7933533402912433 -0.6087614290087099 -2.247031068533741e-017 -0.8660254037844346 -0.5000000000000071 -1.824898739396858e-017 -0.8660254037844346 -0.5000000000000071 -1.824898739396858e-017 -0.9238795325113181 -0.3826834323650143 -1.371541886870991e-017 -0.9238795325113181 -0.3826834323650143 -1.371541886870991e-017 -0.9659258262890479 -0.2588190451025965 -8.947175723984055e-018 -0.9659258262890479 -0.2588190451025965 -8.947175723984055e-018 -0.991444861373845 -0.130526192219789 -4.025843921976333e-018 -0.991444861373845 -0.130526192219789 -4.025843921976333e-018 -0.9978589232386543 -0.06540312922937021 -1.534020824458279e-018 -0.9978589232386543 -0.06540312922937021 -1.534020824458279e-018 0.1305261922200759 0.9914448613738072 -2.360634470126157e-031 0.0654031292301361 0.997858923238604 -2.362395058420794e-031 0.1305261922200759 0.9914448613738072 -2.360634470126157e-031 0.0654031292301361 0.997858923238604 -2.362395058420794e-031 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -1.671284122841572e-018 2.115224975658733e-017 -1 -0.06540312922959453 0.9978589232386395 -0 -0.1305261922200789 0.9914448613738068 0 -0.06540312922959453 0.9978589232386395 -0 -0.1305261922200789 0.9914448613738068 0 -2.847216503390403e-016 -1 2.354039508393783e-031 -2.847216503390403e-016 -1 2.354039508393783e-031 -2.847216503390403e-016 -1 2.354039508393783e-031 -2.847216503390403e-016 -1 2.354039508393783e-031 -2.847216503390403e-016 -1 2.354039508393783e-031 -0.1305261922203011 -0.9914448613737775 0 -0.06540312923079149 -0.9978589232385611 -0 -0.1305261922203011 -0.9914448613737775 0 -0.06540312923079149 -0.9978589232385611 -0 0.2588190451025202 0.9659258262890684 -2.326838321583154e-031 0.2588190451025202 0.9659258262890684 -2.326838321583154e-031 -0.2588190451024253 -0.9659258262890939 0 -0.2588190451024253 -0.9659258262890939 0 -0.3826834323650169 -0.9238795325113171 0 -0.3826834323650169 -0.9238795325113171 0 -0.4999999999999031 -0.8660254037844946 0 -0.4999999999999031 -0.8660254037844946 0 -0.6087614290086439 -0.7933533402912941 0 -0.6087614290086439 -0.7933533402912941 0 -0.7071067811866093 -0.7071067811864858 0 -0.7071067811866093 -0.7071067811864858 0 -0.7933533402914218 -0.6087614290084773 0 -0.7933533402914218 -0.6087614290084773 0 -0.8660254037845377 -0.4999999999998284 0 -0.8660254037845377 -0.4999999999998284 0 -0.9238795325112122 -0.3826834323652698 0 -0.9238795325112122 -0.3826834323652698 0 -0.9659258262890901 -0.2588190451024401 0 -0.9659258262890901 -0.2588190451024401 0 -0.9914448613738833 -0.1305261922194982 0 -0.9914448613738833 -0.1305261922194982 0 -0.997858923238638 -0.06540312922961909 -0 -0.997858923238638 -0.06540312922961909 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -0.9978589232386694 0.06540312922913877 -0 -0.9914448613739054 0.1305261922193298 0 -0.9914448613739054 0.1305261922193298 0 -0.9978589232386694 0.06540312922913877 -0 -0.9659258262890584 0.2588190451025578 0 -0.9659258262890584 0.2588190451025578 0 -0.923879532511276 0.3826834323651157 0 -0.923879532511276 0.3826834323651157 0 -0.8660254037843593 0.5000000000001372 0 -0.8660254037843593 0.5000000000001372 0 -0.793353340290994 0.608761429009035 0 -0.793353340290994 0.608761429009035 0 -0.7071067811861586 0.7071067811869366 0 -0.7071067811861586 0.7071067811869366 0 -0.6087614290088786 0.793353340291114 0 -0.6087614290088786 0.793353340291114 0 -0.5000000000005405 0.8660254037841265 0 -0.5000000000005405 0.8660254037841265 0 -0.3826834323649039 0.9238795325113639 0 -0.3826834323649039 0.9238795325113639 0 -0.2588190451027368 0.9659258262890103 0 -0.2588190451027368 0.9659258262890103 0 0.0654031292301436 -0.9978589232386035 2.33560359979311e-031 0.1305261922200579 -0.9914448613738096 2.307166278009732e-031 0.0654031292301436 -0.9978589232386035 2.33560359979311e-031 0.1305261922200579 -0.9914448613738096 2.307166278009732e-031 0.382683432365069 0.9238795325112953 -2.253229324236416e-031 0.382683432365069 0.9238795325112953 -2.253229324236416e-031 0.2588190451025239 -0.9659258262890675 2.220816792941599e-031 0.2588190451025239 -0.9659258262890675 2.220816792941599e-031 0.5000000000000147 0.8660254037844301 -2.141066948438753e-031 0.5000000000000147 0.8660254037844301 -2.141066948438753e-031 0.3826834323650852 -0.9238795325112886 2.096468516819501e-031 0.3826834323650852 -0.9238795325112886 2.096468516819501e-031 0.6087614290087049 0.7933533402912473 -1.992270323537472e-031 0.6087614290087049 0.7933533402912473 -1.992270323537472e-031 0.4999999999999988 -0.8660254037844394 1.936249083123728e-031 0.4999999999999988 -0.8660254037844394 1.936249083123728e-031 0.7071067811865293 0.7071067811865658 -1.809385401038751e-031 0.7071067811865293 0.7071067811865658 -1.809385401038751e-031 0.6087614290087232 -0.7933533402912332 1.742899890786038e-031 0.6087614290087232 -0.7933533402912332 1.742899890786038e-031 0.7933533402912396 0.6087614290087149 -1.595541392671784e-031 0.7933533402912396 0.6087614290087149 -1.595541392671784e-031 0.7071067811865497 -0.7071067811865455 1.519729198093864e-031 0.7071067811865497 -0.7071067811865455 1.519729198093864e-031 0.8660254037844386 0.4999999999999999 -1.35439722870862e-031 0.8660254037844386 0.4999999999999999 -1.35439722870862e-031 0.7933533402912354 -0.6087614290087204 1.270555517473774e-031 0.7933533402912354 -0.6087614290087204 1.270555517473774e-031 0.9238795325112905 0.3826834323650806 -1.090078952652364e-031 0.9238795325112905 0.3826834323650806 -1.090078952652364e-031 0.8660254037844404 -0.4999999999999971 9.996422796851562e-032 0.8660254037844404 -0.4999999999999971 9.996422796851562e-032 0.9659258262890674 0.258819045102524 -8.071091234892916e-032 0.9659258262890674 0.258819045102524 -8.071091234892916e-032 0.9238795325112879 -0.3826834323650874 7.116248853379323e-032 0.9238795325112879 -0.3826834323650874 7.116248853379323e-032 0.9914448613738091 0.1305261922200617 -5.103294334503805e-032 0.9914448613738091 0.1305261922200617 -5.103294334503805e-032 0.965925826289068 -0.2588190451025222 4.114313919028921e-032 0.965925826289068 -0.2588190451025222 4.114313919028921e-032 0.9978589232386044 0.06540312923013249 -3.583408847236163e-032 0.9978589232386044 0.06540312923013249 -3.583408847236163e-032 0.9914448613738105 -0.1305261922200517 1.041981932820484e-032 0.9914448613738105 -0.1305261922200517 1.041981932820484e-032 1 -3.846068690370998e-016 -2.04817865315044e-032 1 -3.846068690370998e-016 -2.04817865315044e-032 1 -3.846068690370998e-016 -2.04817865315044e-032 1 -3.846068690370998e-016 -2.04817865315044e-032 0.9978589232386037 -0.0654031292301418 -5.041778436296195e-033 0.9978589232386037 -0.0654031292301418 -5.041778436296195e-033 + + + + + + + + + + + + + + +

0 1 2 1 0 3 4 5 6 5 4 2 2 4 0 3 7 1 7 3 8 9 10 11 10 9 12 12 9 13 13 9 14 14 9 15 15 9 16 16 9 17 17 9 18 18 9 19 18 19 20 18 20 21 21 20 22 21 22 23 23 22 24 24 22 25 24 25 26 26 25 27 26 27 28 26 28 29 29 28 30 30 28 31 30 31 32 30 32 33 33 32 34 33 34 35 35 34 36 36 34 37 36 37 38 38 37 39 38 39 40 40 39 41 42 17 43 17 42 44 17 44 45 17 45 46 17 46 47 17 47 16 48 49 50 49 48 51 52 53 54 53 52 55 53 55 56 57 54 53 8 58 7 58 8 59 60 61 62 61 60 63 64 65 66 65 64 67 66 68 69 68 66 65 69 70 71 70 69 68 71 72 73 72 71 70 73 74 75 74 73 72 75 76 77 76 75 74 78 76 79 76 78 77 80 79 81 79 80 78 82 81 83 81 82 80 84 83 85 83 84 82 86 85 87 85 86 84 88 87 89 87 88 86 90 58 59 58 90 91 92 91 90 91 92 93 94 93 92 93 94 95 96 95 94 95 96 97 98 97 96 97 98 99 100 99 98 99 100 101 102 101 100 101 102 103 102 104 103 104 102 105 106 107 108 107 106 109 110 111 112 111 110 113 111 113 114 114 113 115 116 117 118 117 116 119 120 118 121 118 120 116 122 121 123 121 122 120 124 123 125 123 124 122 126 125 127 125 126 124 128 127 129 127 128 126 128 130 131 130 128 129 131 132 133 132 131 130 133 134 135 134 133 132 135 136 137 136 135 134 137 138 139 138 137 136 139 140 141 140 139 138 142 143 144 143 142 145 146 147 148 147 146 149 149 146 150 150 146 151 151 146 152 152 146 153 153 146 154 154 146 155 155 146 156 156 146 157 157 146 158 158 146 159 159 146 160 161 162 163 162 161 164 162 164 165 162 165 166 162 166 167 162 167 168 162 168 169 162 169 170 162 170 171 162 171 172 162 172 173 162 173 160 162 160 146 162 146 174 162 174 175 175 174 176 176 174 177 176 177 178 178 177 179 178 179 180 180 179 181 180 181 182 180 182 183 183 182 184 184 182 185 184 185 186 186 185 187 186 187 188 188 187 189 188 189 190 188 190 191 191 190 192 191 192 193 193 192 194 193 194 195 195 194 196 195 196 197 198 199 200 199 198 201 202 203 204 203 202 205 205 202 206 207 208 209 208 207 210 211 144 212 144 211 142 213 209 214 209 213 207 215 214 216 214 215 213 217 216 218 216 217 215 219 218 220 218 219 217 221 220 222 220 221 219 221 223 224 223 221 222 224 225 226 225 224 223 226 227 228 227 226 225 228 229 230 229 228 227 230 231 232 231 230 229 232 233 234 233 232 231 235 236 237 236 235 238 239 240 241 240 239 242 241 243 244 243 241 240 244 245 246 245 244 243 246 247 248 247 246 245 248 249 250 249 248 247 250 251 252 251 250 249 253 251 254 251 253 252 255 254 256 254 255 253 257 256 258 256 257 255 259 258 260 258 259 257 201 260 199 260 201 259 261 262 263 262 261 264 265 212 266 212 265 211 264 267 262 267 264 268 269 266 270 266 269 265 268 271 267 271 268 272 273 270 274 270 273 269 272 275 271 275 272 276 277 274 278 274 277 273 276 279 275 279 276 280 281 277 278 277 281 282 280 283 279 283 280 284 285 282 281 282 285 286 283 287 288 287 283 284 289 286 285 286 289 290 288 291 292 291 288 287 293 290 289 290 293 294 292 295 296 295 292 291 297 294 293 294 297 298 296 299 300 299 296 295 301 298 297 298 301 302 300 303 304 303 300 299 305 306 307 306 305 308 304 309 310 309 304 303

+
+
+
+ + + + 43.38400397036494 7.421059675912715 0.07874015748031579 43.37882183390003 3.127233759244795 0.07874015748031607 43.37882183390003 7.395007316609055 0.07874015748031579 43.38055912121086 3.10072787694619 0.07874015748031607 43.38574125767577 3.074675517642528 0.07874015748031607 43.39254228819227 7.446212749130662 0.07874015748031579 43.39427957550313 3.04952244442458 0.07874015748031607 43.40429069439674 7.470036160206389 0.07874015748031579 43.4060279817076 3.025699033348864 0.07874015748031607 43.4132129304469 7.39162008924713 0.07874015748031579 43.41904817049088 7.492122283971291 0.07874015748031579 43.41729449628541 7.412139506376729 0.07874015748031579 43.42438369328506 7.43302360729623 0.07874015748031579 43.43656221196721 7.512093220724323 0.07874015748031579 43.4341381633926 7.452803715947015 0.07874015748031579 43.44639100492 7.47114138918596 0.07874015748031579 43.45653314872024 7.529607262200647 0.07874015748031579 43.46093256835167 7.487722864339863 0.07874015748031579 43.47861927248514 7.544364738294798 0.07874015748031579 43.47751404350557 7.502264427771523 0.07874015748031579 43.49585171674453 7.514517269298941 0.07874015748031579 43.50244268356087 7.556113144499255 0.07874015748031579 43.51563182539531 7.524271739406478 0.07874015748031579 43.52759575677882 7.56465146232659 0.07874015748031579 43.53651592631481 7.531360936406135 0.07874015748031579 43.55364811608248 7.569833598791506 0.07874015748031579 43.55703534344437 7.535442502244626 0.07874015748031579 50.144256319116 7.569833598791506 0.07874015748031607 50.14313047118674 7.535442502244621 0.07874015748031607 50.16626363075097 7.53392627486092 0.07874015748031607 50.1707622014146 7.568096311480678 0.07874015748031607 50.18789439118228 7.529623649095314 0.07874015748031607 50.19681456071828 7.562914175015767 0.07874015748031607 50.20877849210176 7.522534452095655 0.07874015748031607 50.22196763393622 7.554375857188427 0.07874015748031607 50.22855860075256 7.512779981988107 0.07874015748031607 50.24579104501194 7.542627450983966 0.07874015748031607 50.24689627399151 7.500527140460703 0.07874015748031607 50.26787716877683 7.527869974889834 0.07874015748031607 50.26347774914542 7.485985577029031 0.07874015748031607 50.27801931257708 7.469404101875151 0.07874015748031607 50.28784810552988 7.510355933413502 0.07874015748031607 50.29027215410449 7.451066428636207 0.07874015748031607 50.3053621470062 7.490384996660477 0.07874015748031607 50.30002662421204 7.431286319985366 0.07874015748031607 50.30711582121172 7.410402219065904 0.07874015748031607 50.32011962310036 7.468298872895575 0.07874015748031607 50.31141844697731 7.388771458634578 0.07874015748031607 50.31293467436102 7.365638299070358 0.07874015748031607 50.31293467436102 3.128359607174147 0.07874015748031607 50.32011962310035 3.025699033348873 0.07874015748031607 50.33186802930481 3.049522444424608 0.07874015748031607 50.3318680293048 7.44447546181984 0.07874015748031607 50.34040634713218 7.419322388601879 0.07874015748031607 50.34040634713214 3.074675517642548 0.07874015748031607 50.34558848359704 3.100727876946217 0.07874015748031607 50.34558848359706 7.393270029298235 0.07874015748031607 50.3473257709079 3.127233759244805 0.07874015748031607 50.3473257709079 7.366764146999632 0.07874015748031607 43.4132129304469 3.128359607174164 0.07874015748031607 43.42078545780171 3.003612909583954 0.07874015748031607 43.41472915783061 3.105226447609857 0.07874015748031607 43.41903178359623 3.083595687178518 0.07874015748031607 43.4261209805959 3.062711586259032 0.07874015748031607 43.43829949927805 2.98364197283092 0.07874015748031607 43.43587545070344 3.042931477608274 0.07874015748031607 43.44812829223088 3.024593804369232 0.07874015748031607 43.45827043603106 2.96612793135459 0.07874015748031607 43.46266985566252 3.008012329215369 0.07874015748031607 43.480356559796 2.951370455260453 0.07874015748031607 43.47925133081637 2.993470765783733 0.07874015748031607 43.49758900405537 2.981217924256313 0.07874015748031607 43.5041799708717 2.939622049055988 0.07874015748031607 43.51736911270614 2.971463454148768 0.07874015748031607 43.52933304408965 2.931083731228659 0.07874015748031607 43.53825321362565 2.964374257149114 0.07874015748031607 43.55538540339332 2.925901594763743 0.07874015748031607 43.55988397405696 2.960071631383501 0.07874015748031607 43.58189128569192 2.924164307452924 0.07874015748031607 43.58301713362136 2.958555403999797 0.07874015748031607 50.14425631911599 2.924164307452924 0.07874015748031607 50.14313047118665 2.958555403999804 0.07874015748031607 50.166263630751 2.960071631383512 0.07874015748031607 50.17076220141464 2.925901594763754 0.07874015748031607 50.1878943911823 2.96437425714911 0.07874015748031607 50.19681456071832 2.931083731228657 0.07874015748031607 50.20877849210176 2.971463454148789 0.07874015748031607 50.22196763393622 2.939622049056019 0.07874015748031607 50.22855860075259 2.981217924256331 0.07874015748031607 50.24579104501196 2.951370455260466 0.07874015748031607 50.24689627399157 2.993470765783735 0.07874015748031607 50.26787716877688 2.966127931354595 0.07874015748031607 50.26347774914544 3.008012329215407 0.07874015748031607 50.27801931257705 3.024593804369262 0.07874015748031607 50.28784810552991 2.98364197283095 0.07874015748031607 50.2902721541045 3.042931477608267 0.07874015748031607 50.3053621470062 3.003612909583975 0.07874015748031607 50.30002662421204 3.062711586259064 0.07874015748031607 50.30711582121167 3.083595687178512 0.07874015748031607 50.31141844697729 3.105226447609863 0.07874015748031607 50.144256319116 7.569833598791506 1.090510587941475e-015 43.55364811608248 7.569833598791506 0.07874015748031579 43.55364811608248 7.569833598791506 8.326672684688674e-016 50.144256319116 7.569833598791506 0.07874015748031607 50.1707622014146 7.568096311480678 0.07874015748031607 50.144256319116 7.569833598791506 1.090510587941475e-015 50.1707622014146 7.568096311480678 1.090510587941475e-015 50.144256319116 7.569833598791506 0.07874015748031607 50.19681456071828 7.562914175015767 0.07874015748031607 50.19681456071828 7.562914175015767 1.090510587941475e-015 50.22196763393622 7.554375857188427 0.07874015748031607 50.22196763393622 7.554375857188427 1.090510587941475e-015 50.24579104501194 7.542627450983966 0.07874015748031607 50.24579104501194 7.542627450983966 1.090510587941475e-015 50.26787716877683 7.527869974889834 0.07874015748031607 50.26787716877683 7.527869974889834 1.090510587941475e-015 50.28784810552988 7.510355933413502 0.07874015748031607 50.28784810552988 7.510355933413502 1.090510587941475e-015 50.3053621470062 7.490384996660477 1.090510587941475e-015 50.3053621470062 7.490384996660477 0.07874015748031607 50.32011962310036 7.468298872895575 1.118266163557104e-015 50.32011962310036 7.468298872895575 0.07874015748031607 50.3318680293048 7.44447546181984 1.118266163557104e-015 50.3318680293048 7.44447546181984 0.07874015748031607 50.34040634713218 7.419322388601879 1.118266163557104e-015 50.34040634713218 7.419322388601879 0.07874015748031607 50.34558848359706 7.393270029298235 1.118266163557104e-015 50.34558848359706 7.393270029298235 0.07874015748031607 50.3473257709079 7.366764146999632 1.118266163557104e-015 50.3473257709079 7.366764146999632 0.07874015748031607 50.3473257709079 7.366764146999632 0.07874015748031607 50.3473257709079 3.127233759244805 1.103017739216966e-015 50.3473257709079 3.127233759244805 0.07874015748031607 50.3473257709079 7.366764146999632 1.118266163557104e-015 50.3473257709079 3.127233759244805 0.07874015748031607 50.34558848359704 3.100727876946217 1.105899590885709e-015 50.34558848359704 3.100727876946217 0.07874015748031607 50.3473257709079 3.127233759244805 1.103017739216966e-015 50.34040634713214 3.074675517642548 1.108591182719098e-015 50.34040634713214 3.074675517642548 0.07874015748031607 50.33186802930481 3.049522444424608 1.111046460834616e-015 50.33186802930481 3.049522444424608 0.07874015748031607 50.32011962310035 3.025699033348873 1.113223414742969e-015 50.32011962310035 3.025699033348873 0.07874015748031607 50.3053621470062 3.003612909583975 1.115084796159225e-015 50.3053621470062 3.003612909583975 0.07874015748031607 50.28784810552991 2.98364197283095 1.116598756331273e-015 50.28784810552991 2.98364197283095 0.07874015748031607 50.26787716877688 2.966127931354595 1.11773939098083e-015 50.26787716877688 2.966127931354595 0.07874015748031607 50.24579104501196 2.951370455260466 1.11848718353279e-015 50.24579104501196 2.951370455260466 0.07874015748031607 50.22196763393622 2.939622049056019 1.118829339049262e-015 50.22196763393622 2.939622049056019 0.07874015748031607 50.19681456071832 2.931083731228657 0.07874015748031607 50.19681456071832 2.931083731228657 1.118760003154504e-015 50.17076220141464 2.925901594763754 0.07874015748031607 50.17076220141464 2.925901594763754 1.118280362204888e-015 50.14425631911599 2.924164307452924 0.07874015748031607 50.14425631911599 2.924164307452924 1.117398622990049e-015 43.58189128569192 2.924164307452924 0.07874015748031607 50.14425631911599 2.924164307452924 1.117398622990049e-015 43.58189128569192 2.924164307452924 1.109233975091996e-015 50.14425631911599 2.924164307452924 0.07874015748031607 43.55538540339332 2.925901594763743 1.109463768595622e-015 43.58189128569192 2.924164307452924 0.07874015748031607 43.58189128569192 2.924164307452924 1.109233975091996e-015 43.55538540339332 2.925901594763743 0.07874015748031607 43.52933304408965 2.931083731228659 0.07874015748031607 43.52933304408965 2.931083731228659 1.109462778393509e-015 43.5041799708717 2.939622049055988 0.07874015748031607 43.5041799708717 2.939622049055988 1.109231021428294e-015 43.480356559796 2.951370455260453 0.07874015748031607 43.480356559796 2.951370455260453 1.108772463125903e-015 43.45827043603106 2.96612793135459 0.07874015748031607 43.45827043603106 2.96612793135459 1.108094949546031e-015 43.43829949927805 2.98364197283092 0.07874015748031607 43.43829949927805 2.98364197283092 1.107210073133866e-015 43.42078545780171 3.003612909583954 1.106132974370159e-015 43.42078545780171 3.003612909583954 0.07874015748031607 43.4060279817076 3.025699033348864 1.104882082713383e-015 43.4060279817076 3.025699033348864 0.07874015748031607 43.39427957550313 3.04952244442458 1.1034788012666e-015 43.39427957550313 3.04952244442458 0.07874015748031607 43.38574125767577 3.074675517642528 1.101947140564425e-015 43.38574125767577 3.074675517642528 0.07874015748031607 43.38055912121086 3.10072787694619 1.100313307746131e-015 43.38055912121086 3.10072787694619 0.07874015748031607 43.37882183390003 3.127233759244795 1.098605258144222e-015 43.37882183390003 3.127233759244795 0.07874015748031607 43.37882183390003 7.395007316609055 8.326672684688674e-016 43.37882183390003 3.127233759244795 0.07874015748031607 43.37882183390003 3.127233759244795 1.098605258144222e-015 43.37882183390003 7.395007316609055 0.07874015748031579 43.38400397036494 7.421059675912715 8.326672684688674e-016 43.37882183390003 7.395007316609055 0.07874015748031579 43.37882183390003 7.395007316609055 8.326672684688674e-016 43.38400397036494 7.421059675912715 0.07874015748031579 43.39254228819227 7.446212749130662 8.326672684688674e-016 43.39254228819227 7.446212749130662 0.07874015748031579 43.40429069439674 7.470036160206389 8.326672684688674e-016 43.40429069439674 7.470036160206389 0.07874015748031579 43.41904817049088 7.492122283971291 8.326672684688674e-016 43.41904817049088 7.492122283971291 0.07874015748031579 43.43656221196721 7.512093220724323 8.326672684688674e-016 43.43656221196721 7.512093220724323 0.07874015748031579 43.45653314872024 7.529607262200647 0.07874015748031579 43.45653314872024 7.529607262200647 8.326672684688674e-016 43.47861927248514 7.544364738294798 0.07874015748031579 43.47861927248514 7.544364738294798 8.326672684688674e-016 43.50244268356087 7.556113144499255 0.07874015748031579 43.50244268356087 7.556113144499255 8.326672684688674e-016 43.52759575677882 7.56465146232659 0.07874015748031579 43.52759575677882 7.56465146232659 8.326672684688674e-016 43.55364811608248 7.569833598791506 0.07874015748031579 43.55364811608248 7.569833598791506 8.326672684688674e-016 + + + + + + + + + + 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 1.945976020073421e-017 -3.061037150919461e-017 -1 0 -1 0 0 -1 0 0 -1 0 0 -1 0 -0.1305261922199813 -0.9914448613738196 2.780848713701879e-017 -0.06540312923029371 -0.9978589232385937 2.927210314289912e-017 -0.1305261922199813 -0.9914448613738196 2.780848713701879e-017 -0.06540312923029371 -0.9978589232385937 2.927210314289912e-017 -0.2588190451024848 -0.965925826289078 2.453079183995709e-017 -0.2588190451024848 -0.965925826289078 2.453079183995709e-017 -0.382683432365306 -0.9238795325111974 2.083336789328604e-017 -0.382683432365306 -0.9238795325111974 2.083336789328604e-017 -0.5000000000000238 -0.8660254037844249 1.677947924587394e-017 -0.5000000000000238 -0.8660254037844249 1.677947924587394e-017 -0.6087614290084881 -0.7933533402914136 1.24384890564192e-017 -0.6087614290084881 -0.7933533402914136 1.24384890564192e-017 -0.7071067811864248 -0.7071067811866704 7.884672870593892e-018 -0.7071067811864248 -0.7071067811866704 7.884672870593892e-018 -0.7933533402911389 -0.6087614290088461 3.195947745911922e-018 -0.7933533402911389 -0.6087614290088461 3.195947745911922e-018 -0.8660254037845401 -0.4999999999998245 -1.547460930799239e-018 -0.8660254037845401 -0.4999999999998245 -1.54746093079924e-018 -0.923879532511154 -0.3826834323654104 -6.264392121914531e-018 -0.923879532511154 -0.3826834323654104 -6.264392121914531e-018 -0.9659258262890302 -0.2588190451026624 -1.087413782703309e-017 -0.9659258262890302 -0.2588190451026624 -1.087413782703309e-017 -0.9914448613738499 -0.1305261922197522 -1.529782401905813e-017 -0.9914448613738499 -0.1305261922197522 -1.529782401905813e-017 -0.9978589232385668 -0.06540312923070414 -1.741608127676964e-017 -0.9978589232385668 -0.06540312923070414 -1.741608127676964e-017 -1 6.99914032825858e-035 -1.945976020073421e-017 -1 6.99914032825858e-035 -1.945976020073421e-017 -1 6.99914032825858e-035 -1.945976020073421e-017 -1 6.99914032825858e-035 -1.945976020073421e-017 -0.997858923238512 0.06540312923154029 -2.142010944402561e-017 -0.9914448613737562 0.1305261922204639 -2.328873449013242e-017 -0.9914448613737562 0.1305261922204639 -2.328873449013242e-017 -0.997858923238512 0.06540312923154029 -2.142010944402561e-017 -0.9659258262891491 0.2588190451022194 -2.671923207551683e-017 -0.9659258262891491 0.2588190451022194 -2.671923207551682e-017 -0.9238795325113062 0.3826834323650429 -2.969255619214416e-017 -0.9238795325113063 0.3826834323650429 -2.969255619214416e-017 -0.8660254037844481 0.4999999999999837 -3.215783243998618e-017 -0.8660254037844481 0.4999999999999837 -3.215783243998619e-017 -0.7933533402914976 0.6087614290083786 -3.40728792589387e-017 -0.7933533402914977 0.6087614290083787 -3.407287925893871e-017 -0.7071067811871351 0.7071067811859598 -3.540492966698771e-017 -0.707106781187135 0.70710678118596 -3.54049296669877e-017 -0.6087614290086183 0.7933533402913137 -3.61311919123416e-017 -0.6087614290086183 0.7933533402913137 -3.61311919123416e-017 -0.4999999999992923 0.8660254037848472 -3.623923944660778e-017 -0.4999999999992923 0.8660254037848472 -3.623923944660778e-017 -0.3826834323655242 0.9238795325111068 -3.5727223546533e-017 -0.3826834323655242 0.9238795325111068 -3.5727223546533e-017 -0.2588190451029578 0.9659258262889511 -3.460390494611714e-017 -0.2588190451029578 0.9659258262889511 -3.460390494611714e-017 -0.1305261922198164 0.9914448613738415 -3.28885039380478e-017 -0.1305261922198164 0.9914448613738415 -3.28885039380478e-017 -0.06540312923028883 0.997858923238594 -3.181756156529731e-017 -0.06540312923028883 0.997858923238594 -3.181756156529731e-017 6.767212850674795e-017 1 -3.061037150919461e-017 6.767212850674795e-017 1 -3.061037150919461e-017 6.767212850674795e-017 1 -3.061037150919461e-017 6.767212850674795e-017 1 -3.061037150919461e-017 0.1305261922199325 0.991444861373826 -2.780848713701993e-017 0.06540312922994411 0.9978589232386167 -2.927210314290662e-017 0.06540312922994411 0.9978589232386167 -2.927210314290662e-017 0.1305261922199325 0.991444861373826 -2.780848713701993e-017 0.2588190451023891 0.9659258262891036 -2.453079183995972e-017 0.2588190451023891 0.9659258262891036 -2.453079183995972e-017 0.3826834323652765 0.9238795325112095 -2.083336789328698e-017 0.3826834323652765 0.9238795325112095 -2.083336789328698e-017 0.4999999999998008 0.8660254037845535 -1.677947924588222e-017 0.4999999999998008 0.8660254037845535 -1.677947924588222e-017 0.6087614290084553 0.7933533402914387 -1.24384890564206e-017 0.6087614290084553 0.7933533402914387 -1.24384890564206e-017 0.7071067811866578 0.7071067811864372 -7.884672870582221e-018 0.7071067811866578 0.7071067811864372 -7.884672870582221e-018 0.7933533402916122 0.6087614290082292 -3.195947745883828e-018 0.7933533402916122 0.6087614290082292 -3.195947745883828e-018 0.8660254037845893 0.499999999999739 1.547460930802815e-018 0.8660254037845894 0.4999999999997391 1.547460930802815e-018 0.9238795325109803 0.3826834323658298 6.26439212189831e-018 0.9238795325109803 0.3826834323658298 6.26439212189831e-018 0.9659258262889898 0.2588190451028135 1.087413782702768e-017 0.9659258262889898 0.2588190451028135 1.087413782702768e-017 0.9914448613738075 0.1305261922200738 1.529782401904747e-017 0.9914448613738075 0.1305261922200738 1.529782401904747e-017 0.9978589232385846 0.06540312923043123 1.741608127677834e-017 0.9978589232385846 0.06540312923043123 1.741608127677834e-017 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 0.9659258262890843 -0.2588190451024608 1.416353255915568e-017 0.9807852804032251 -0.1950903220161558 -0 0.9807852804032251 -0.1950903220161558 -0 0.9659258262890843 -0.2588190451024608 1.416353255915568e-017 0.9238795325112965 -0.3826834323650666 2.96925561921447e-017 0.9238795325112965 -0.3826834323650666 2.96925561921447e-017 0.8660254037844343 -0.5000000000000074 3.215783243998664e-017 0.8660254037844343 -0.5000000000000074 3.215783243998664e-017 0.7933533402912668 -0.6087614290086795 3.407287925894342e-017 0.7933533402912668 -0.6087614290086795 3.407287925894342e-017 0.7071067811865319 -0.707106781186563 3.540492966699442e-017 0.7071067811865319 -0.707106781186563 3.540492966699442e-017 0.6087614290087207 -0.7933533402912351 3.613119191234118e-017 0.6087614290087207 -0.7933533402912351 3.613119191234118e-017 0.4999999999999814 -0.8660254037844495 3.623923944660901e-017 0.4999999999999814 -0.8660254037844495 3.623923944660901e-017 0.382683432365068 -0.9238795325112956 3.572722354652991e-017 0.382683432365068 -0.9238795325112956 3.572722354652991e-017 0.2588190451025379 -0.9659258262890638 1.765831679721354e-017 0.2588190451025379 -0.9659258262890638 1.765831679721354e-017 0.1950903220161044 -0.9807852804032353 0 0.1950903220161044 -0.9807852804032353 0 + + + + + + + + + + + + + + +

0 1 2 1 0 3 3 0 4 4 0 5 4 5 6 6 5 7 6 7 8 8 7 9 9 7 10 9 10 11 11 10 12 12 10 13 12 13 14 14 13 15 15 13 16 15 16 17 17 16 18 17 18 19 19 18 20 20 18 21 20 21 22 22 21 23 22 23 24 24 23 25 24 25 26 26 25 27 26 27 28 28 27 29 29 27 30 29 30 31 31 30 32 31 32 33 33 32 34 33 34 35 35 34 36 35 36 37 37 36 38 37 38 39 39 38 40 40 38 41 40 41 42 42 41 43 42 43 44 44 43 45 45 43 46 45 46 47 47 46 48 48 46 49 49 46 50 50 46 51 51 46 52 51 52 53 51 53 54 54 53 55 55 53 56 55 56 57 57 56 58 8 59 60 59 8 9 60 59 61 60 61 62 60 62 63 60 63 64 64 63 65 64 65 66 64 66 67 67 66 68 67 68 69 69 68 70 69 70 71 69 71 72 72 71 73 72 73 74 74 73 75 74 75 76 76 75 77 76 77 78 78 77 79 78 79 80 80 79 81 80 81 82 80 82 83 83 82 84 83 84 85 85 84 86 85 86 87 87 86 88 87 88 89 89 88 90 89 90 91 91 90 92 91 92 93 91 93 94 94 93 95 94 95 96 96 95 97 96 97 98 96 98 50 50 98 99 50 99 49 100 101 102 101 100 103 104 105 106 105 104 107 108 106 109 106 108 104 110 109 111 109 110 108 112 111 113 111 112 110 114 113 115 113 114 112 116 115 117 115 116 114 116 118 119 118 116 117 119 120 121 120 119 118 121 122 123 122 121 120 123 124 125 124 123 122 125 126 127 126 125 124 127 128 129 128 127 126 130 131 132 131 130 133 134 135 136 135 134 137 136 138 139 138 136 135 139 140 141 140 139 138 141 142 143 142 141 140 143 144 145 144 143 142 145 146 147 146 145 144 148 147 146 147 148 149 150 149 148 149 150 151 152 151 150 151 152 153 154 152 155 152 154 153 156 155 157 155 156 154 158 157 159 157 158 156 160 161 162 161 160 163 164 165 166 165 164 167 168 164 169 164 168 167 170 169 171 169 170 168 172 171 173 171 172 170 174 173 175 173 174 172 176 175 177 175 176 174 178 176 177 176 178 179 180 179 178 179 180 181 182 181 180 181 182 183 184 183 182 183 184 185 186 185 184 185 186 187 188 187 186 187 188 189 190 191 192 191 190 193 194 195 196 195 194 197 198 197 194 197 198 199 200 199 198 199 200 201 202 201 200 201 202 203 204 203 202 203 204 205 206 204 207 204 206 205 208 207 209 207 208 206 210 209 211 209 210 208 212 211 213 211 212 210 214 213 215 213 214 212

+
+
+
+ + + + 43.41729449628541 7.412139506376729 -0.1968503937007866 43.4132129304469 3.128359607174164 -0.1968503937007863 43.4132129304469 7.39162008924713 -0.1968503937007866 43.41472915783061 3.105226447609857 -0.1968503937007863 43.41903178359623 3.083595687178518 -0.1968503937007863 43.42438369328506 7.43302360729623 -0.1968503937007866 43.4261209805959 3.062711586259032 -0.1968503937007863 43.4341381633926 7.452803715947015 -0.1968503937007866 43.43587545070344 3.042931477608274 -0.1968503937007863 43.44639100492 7.47114138918596 -0.1968503937007866 43.44812829223088 3.024593804369232 -0.1968503937007863 43.46093256835167 7.487722864339863 -0.1968503937007866 43.46266985566252 3.008012329215369 -0.1968503937007863 43.47751404350557 7.502264427771523 -0.1968503937007866 43.47925133081637 2.993470765783733 -0.1968503937007863 43.49585171674453 7.514517269298941 -0.1968503937007866 43.49758900405537 2.981217924256313 -0.1968503937007863 43.51563182539531 7.524271739406478 -0.1968503937007866 43.51736911270614 2.971463454148768 -0.1968503937007863 43.53651592631481 7.531360936406135 -0.1968503937007866 43.53825321362565 2.964374257149114 -0.1968503937007863 43.55703534344437 7.535442502244626 -0.1968503937007866 43.55988397405696 2.960071631383501 -0.1968503937007863 50.14313047118674 7.535442502244621 -0.1968503937007863 43.58301713362136 2.958555403999797 -0.1968503937007863 50.14313047118665 2.958555403999804 -0.1968503937007863 50.166263630751 2.960071631383512 -0.1968503937007863 50.16626363075097 7.53392627486092 -0.1968503937007863 50.18789439118228 7.529623649095314 -0.1968503937007863 50.1878943911823 2.96437425714911 -0.1968503937007863 50.20877849210176 7.522534452095655 -0.1968503937007863 50.20877849210176 2.971463454148789 -0.1968503937007863 50.22855860075256 7.512779981988107 -0.1968503937007863 50.22855860075259 2.981217924256331 -0.1968503937007863 50.24689627399151 7.500527140460703 -0.1968503937007863 50.24689627399157 2.993470765783735 -0.1968503937007863 50.26347774914542 7.485985577029031 -0.1968503937007863 50.26347774914544 3.008012329215407 -0.1968503937007863 50.27801931257708 7.469404101875151 -0.1968503937007863 50.27801931257705 3.024593804369262 -0.1968503937007863 50.2902721541045 3.042931477608267 -0.1968503937007863 50.29027215410449 7.451066428636207 -0.1968503937007863 50.30002662421204 7.431286319985366 -0.1968503937007863 50.30002662421204 3.062711586259064 -0.1968503937007863 50.30711582121172 7.410402219065904 -0.1968503937007863 50.30711582121167 3.083595687178512 -0.1968503937007863 50.31141844697729 3.105226447609863 -0.1968503937007863 50.31141844697731 7.388771458634578 -0.1968503937007863 50.31293467436102 3.128359607174147 -0.1968503937007863 50.31293467436102 7.365638299070358 -0.1968503937007863 + + + + + + + + + + 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 1.95818153218181e-017 -2.97996970582078e-017 -1 + + + + + + + + + + + + + + +

0 1 2 1 0 3 3 0 4 4 0 5 4 5 6 6 5 7 6 7 8 8 7 9 8 9 10 10 9 11 10 11 12 12 11 13 12 13 14 14 13 15 14 15 16 16 15 17 16 17 18 18 17 19 18 19 20 20 19 21 20 21 22 22 21 23 22 23 24 24 23 25 25 23 26 26 23 27 26 27 28 26 28 29 29 28 30 29 30 31 31 30 32 31 32 33 33 32 34 33 34 35 35 34 36 35 36 37 37 36 38 37 38 39 39 38 40 40 38 41 40 41 42 40 42 43 43 42 44 43 44 45 45 44 46 46 44 47 46 47 48 48 47 49

+
+
+
+ + + + 50.31141844697731 7.388771458634578 -0.1968503937007863 50.31293467436102 7.365638299070358 0.07874015748031607 50.31293467436102 7.365638299070358 -0.1968503937007863 50.31141844697731 7.388771458634578 0.07874015748031607 50.31293467436102 7.365638299070358 -0.1968503937007863 50.31293467436102 3.128359607174147 0.07874015748031607 50.31293467436102 3.128359607174147 -0.1968503937007863 50.31293467436102 7.365638299070358 0.07874015748031607 50.30711582121172 7.410402219065904 -0.1968503937007863 50.30711582121172 7.410402219065904 0.07874015748031607 50.31293467436102 3.128359607174147 -0.1968503937007863 50.31141844697729 3.105226447609863 0.07874015748031607 50.31141844697729 3.105226447609863 -0.1968503937007863 50.31293467436102 3.128359607174147 0.07874015748031607 50.30002662421204 7.431286319985366 -0.1968503937007863 50.30002662421204 7.431286319985366 0.07874015748031607 50.30711582121167 3.083595687178512 0.07874015748031607 50.30711582121167 3.083595687178512 -0.1968503937007863 50.29027215410449 7.451066428636207 -0.1968503937007863 50.29027215410449 7.451066428636207 0.07874015748031607 50.30002662421204 3.062711586259064 0.07874015748031607 50.30002662421204 3.062711586259064 -0.1968503937007863 50.27801931257708 7.469404101875151 -0.1968503937007863 50.27801931257708 7.469404101875151 0.07874015748031607 50.2902721541045 3.042931477608267 0.07874015748031607 50.2902721541045 3.042931477608267 -0.1968503937007863 50.26347774914542 7.485985577029031 -0.1968503937007863 50.26347774914542 7.485985577029031 0.07874015748031607 50.27801931257705 3.024593804369262 0.07874015748031607 50.27801931257705 3.024593804369262 -0.1968503937007863 50.24689627399151 7.500527140460703 0.07874015748031607 50.24689627399151 7.500527140460703 -0.1968503937007863 50.26347774914544 3.008012329215407 0.07874015748031607 50.26347774914544 3.008012329215407 -0.1968503937007863 50.22855860075256 7.512779981988107 0.07874015748031607 50.22855860075256 7.512779981988107 -0.1968503937007863 50.24689627399157 2.993470765783735 -0.1968503937007863 50.24689627399157 2.993470765783735 0.07874015748031607 50.20877849210176 7.522534452095655 0.07874015748031607 50.20877849210176 7.522534452095655 -0.1968503937007863 50.22855860075259 2.981217924256331 -0.1968503937007863 50.22855860075259 2.981217924256331 0.07874015748031607 50.18789439118228 7.529623649095314 0.07874015748031607 50.18789439118228 7.529623649095314 -0.1968503937007863 50.20877849210176 2.971463454148789 -0.1968503937007863 50.20877849210176 2.971463454148789 0.07874015748031607 50.16626363075097 7.53392627486092 0.07874015748031607 50.16626363075097 7.53392627486092 -0.1968503937007863 50.1878943911823 2.96437425714911 -0.1968503937007863 50.1878943911823 2.96437425714911 0.07874015748031607 50.14313047118674 7.535442502244621 0.07874015748031607 50.14313047118674 7.535442502244621 -0.1968503937007863 50.166263630751 2.960071631383512 -0.1968503937007863 50.166263630751 2.960071631383512 0.07874015748031607 43.55703534344437 7.535442502244626 0.07874015748031579 50.14313047118674 7.535442502244621 -0.1968503937007863 43.55703534344437 7.535442502244626 -0.1968503937007866 50.14313047118674 7.535442502244621 0.07874015748031607 50.14313047118665 2.958555403999804 -0.1968503937007863 50.14313047118665 2.958555403999804 0.07874015748031607 43.53651592631481 7.531360936406135 0.07874015748031579 43.55703534344437 7.535442502244626 -0.1968503937007866 43.53651592631481 7.531360936406135 -0.1968503937007866 43.55703534344437 7.535442502244626 0.07874015748031579 50.14313047118665 2.958555403999804 0.07874015748031607 43.58301713362136 2.958555403999797 -0.1968503937007863 50.14313047118665 2.958555403999804 -0.1968503937007863 43.58301713362136 2.958555403999797 0.07874015748031607 43.51563182539531 7.524271739406478 0.07874015748031579 43.51563182539531 7.524271739406478 -0.1968503937007866 43.58301713362136 2.958555403999797 0.07874015748031607 43.55988397405696 2.960071631383501 -0.1968503937007863 43.58301713362136 2.958555403999797 -0.1968503937007863 43.55988397405696 2.960071631383501 0.07874015748031607 43.49585171674453 7.514517269298941 0.07874015748031579 43.49585171674453 7.514517269298941 -0.1968503937007866 43.53825321362565 2.964374257149114 -0.1968503937007863 43.53825321362565 2.964374257149114 0.07874015748031607 43.47751404350557 7.502264427771523 0.07874015748031579 43.47751404350557 7.502264427771523 -0.1968503937007866 43.51736911270614 2.971463454148768 -0.1968503937007863 43.51736911270614 2.971463454148768 0.07874015748031607 43.46093256835167 7.487722864339863 0.07874015748031579 43.46093256835167 7.487722864339863 -0.1968503937007866 43.49758900405537 2.981217924256313 -0.1968503937007863 43.49758900405537 2.981217924256313 0.07874015748031607 43.44639100492 7.47114138918596 -0.1968503937007866 43.44639100492 7.47114138918596 0.07874015748031579 43.47925133081637 2.993470765783733 -0.1968503937007863 43.47925133081637 2.993470765783733 0.07874015748031607 43.4341381633926 7.452803715947015 -0.1968503937007866 43.4341381633926 7.452803715947015 0.07874015748031579 43.46266985566252 3.008012329215369 -0.1968503937007863 43.46266985566252 3.008012329215369 0.07874015748031607 43.42438369328506 7.43302360729623 -0.1968503937007866 43.42438369328506 7.43302360729623 0.07874015748031579 43.44812829223088 3.024593804369232 0.07874015748031607 43.44812829223088 3.024593804369232 -0.1968503937007863 43.41729449628541 7.412139506376729 -0.1968503937007866 43.41729449628541 7.412139506376729 0.07874015748031579 43.43587545070344 3.042931477608274 0.07874015748031607 43.43587545070344 3.042931477608274 -0.1968503937007863 43.4132129304469 7.39162008924713 -0.1968503937007866 43.4132129304469 7.39162008924713 0.07874015748031579 43.4261209805959 3.062711586259032 0.07874015748031607 43.4261209805959 3.062711586259032 -0.1968503937007863 43.4132129304469 7.39162008924713 0.07874015748031579 43.4132129304469 3.128359607174164 -0.1968503937007863 43.4132129304469 3.128359607174164 0.07874015748031607 43.4132129304469 7.39162008924713 -0.1968503937007866 43.41903178359623 3.083595687178518 0.07874015748031607 43.41903178359623 3.083595687178518 -0.1968503937007863 43.4132129304469 3.128359607174164 0.07874015748031607 43.41472915783061 3.105226447609857 -0.1968503937007863 43.41472915783061 3.105226447609857 0.07874015748031607 43.4132129304469 3.128359607174164 -0.1968503937007863 + + + + + + + + + + 0.9914448613738508 0.1305261922197449 1.55246491908785e-017 0.9978589232385636 0.06540312923075399 1.759089571435054e-017 0.9978589232385636 0.06540312923075399 1.759089571435054e-017 0.9914448613738508 0.1305261922197449 1.55246491908785e-017 1 0 1.95818153218181e-017 1 0 1.95818153218181e-017 1 0 1.95818153218181e-017 1 0 1.95818153218181e-017 0.9659258262890319 0.2588190451026562 1.12018520080126e-017 0.9659258262890319 0.2588190451026562 1.12018520080126e-017 0.9978589232385156 -0.06540312923148701 2.148888258984201e-017 0.9914448613737552 -0.1305261922204699 2.330393116351783e-017 0.9914448613737552 -0.1305261922204699 2.330393116351783e-017 0.9978589232385156 -0.06540312923148701 2.148888258984201e-017 0.9238795325111466 0.3826834323654281 6.687388031556006e-018 0.9238795325111466 0.3826834323654281 6.687388031556006e-018 0.9659258262891463 -0.2588190451022301 2.66273102819097e-017 0.9659258262891463 -0.2588190451022301 2.66273102819097e-017 0.8660254037845753 0.4999999999997635 2.058500991815655e-018 0.8660254037845753 0.4999999999997635 2.058500991815655e-018 0.9238795325113448 -0.3826834323649499 2.949508873891546e-017 0.9238795325113448 -0.3826834323649499 2.949508873891546e-017 0.7933533402911205 0.60876142900887 -2.605607570657765e-018 0.7933533402911205 0.60876142900887 -2.605607570657765e-018 0.866025403784477 -0.4999999999999336 3.18581980500125e-017 0.866025403784477 -0.4999999999999336 3.18581980500125e-017 0.7071067811863823 0.707106781186713 -7.225133465171492e-018 0.7071067811863823 0.707106781186713 -7.225133465171492e-018 0.7933533402914658 -0.6087614290084201 3.367620475970759e-017 0.7933533402914658 -0.6087614290084201 3.367620475970759e-017 0.608761429008534 0.7933533402913785 -1.172103532290912e-017 0.608761429008534 0.7933533402913785 -1.172103532290912e-017 0.7071067811870996 -0.7071067811859956 3.491800226915812e-017 0.7071067811870996 -0.7071067811859956 3.491800226915812e-017 0.5000000000000008 0.8660254037844382 -1.601638701657927e-017 0.5000000000000008 0.8660254037844382 -1.601638701657927e-017 0.6087614290086063 -0.793353340291323 3.556234307869128e-017 0.6087614290086063 -0.793353340291323 3.556234307869128e-017 0.3826834323652957 0.9238795325112014 -2.003769388781576e-017 0.3826834323652957 0.9238795325112014 -2.003769388781576e-017 0.4999999999993188 -0.8660254037848321 3.559820233839578e-017 0.4999999999993188 -0.8660254037848321 3.559820233839578e-017 0.2588190451024929 0.9659258262890758 -2.371615026114718e-017 0.2588190451024929 0.9659258262890758 -2.371615026114718e-017 0.3826834323655604 -0.9238795325110919 3.502496648641106e-017 0.3826834323655604 -0.9238795325110919 3.502496648641106e-017 0.1305261922199533 0.9914448613738235 -2.698881672814551e-017 0.1305261922199533 0.9914448613738235 -2.698881672814551e-017 0.2588190451029568 -0.9659258262889514 3.385244374708522e-017 0.2588190451029568 -0.9659258262889514 3.385244374708522e-017 0.06540312923029935 0.9978589232385934 -2.845518162128279e-017 0.06540312923029935 0.9978589232385934 -2.845518162128279e-017 0.1305261922198004 -0.9914448613738436 3.210069630956563e-017 0.1305261922198004 -0.9914448613738436 3.210069630956563e-017 8.091396214053001e-016 1 -2.979969705820778e-017 8.091396214053001e-016 1 -2.979969705820778e-017 8.091396214053001e-016 1 -2.979969705820778e-017 8.091396214053001e-016 1 -2.979969705820778e-017 0.06540312923028356 -0.9978589232385944 3.101660561739596e-017 0.06540312923028356 -0.9978589232385944 3.101660561739596e-017 -0.2588190451025151 0.9659258262890699 -3.385244374708009e-017 -0.1950903220161407 0.980785280403228 -3.304732689195967e-017 -0.2588190451025151 0.9659258262890699 -3.385244374708009e-017 -0.1950903220161407 0.980785280403228 -3.304732689195967e-017 1.015430344717675e-015 -1 2.979969705820782e-017 1.015430344717675e-015 -1 2.979969705820782e-017 1.015430344717675e-015 -1 2.979969705820782e-017 1.015430344717675e-015 -1 2.979969705820782e-017 -0.3826834323650787 0.9238795325112913 -3.502496648640756e-017 -0.3826834323650787 0.9238795325112913 -3.502496648640756e-017 -0.06540312922995281 -0.9978589232386161 2.845518162129025e-017 -0.1305261922199476 -0.9914448613738243 2.698881672814565e-017 -0.06540312922995281 -0.9978589232386161 2.845518162129025e-017 -0.1305261922199476 -0.9914448613738243 2.698881672814565e-017 -0.5000000000000135 0.8660254037844308 -3.559820233839744e-017 -0.5000000000000135 0.8660254037844308 -3.559820233839744e-017 -0.2588190451023761 -0.9659258262891071 2.371615026115041e-017 -0.2588190451023761 -0.9659258262891071 2.371615026115041e-017 -0.6087614290087011 0.7933533402912499 -3.556234307869096e-017 -0.6087614290087011 0.7933533402912499 -3.556234307869096e-017 -0.3826834323652421 -0.9238795325112237 2.003769388781746e-017 -0.3826834323652421 -0.9238795325112237 2.003769388781746e-017 -0.7071067811865318 0.7071067811865633 -3.491800226916392e-017 -0.7071067811865318 0.7071067811865633 -3.491800226916392e-017 -0.4999999999998345 -0.8660254037845342 1.60163870165854e-017 -0.4999999999998345 -0.8660254037845342 1.60163870165854e-017 -0.7933533402912634 0.6087614290086838 -3.367620475971148e-017 -0.7933533402912634 0.6087614290086838 -3.367620475971148e-017 -0.6087614290084824 -0.7933533402914178 1.172103532291131e-017 -0.6087614290084824 -0.7933533402914178 1.172103532291131e-017 -0.8660254037844439 0.4999999999999909 -3.185819805001356e-017 -0.8660254037844439 0.4999999999999909 -3.185819805001356e-017 -0.7071067811866187 -0.7071067811864763 7.225133465159809e-018 -0.7071067811866187 -0.7071067811864763 7.225133465159809e-018 -0.9238795325113307 0.382683432364984 -2.94950887389162e-017 -0.9238795325113307 0.382683432364984 -2.94950887389162e-017 -0.7933533402916141 -0.6087614290082266 2.605607570628924e-018 -0.7933533402916141 -0.6087614290082266 2.605607570628924e-018 -0.9659258262890716 0.2588190451025084 -2.662731028191653e-017 -0.9659258262890716 0.2588190451025084 -2.662731028191653e-017 -0.8660254037845783 -0.4999999999997583 -2.058500991815872e-018 -0.8660254037845783 -0.4999999999997583 -2.058500991815872e-018 -0.9807852804031837 0.1950903220163633 -2.501918872628857e-017 -0.9807852804031837 0.1950903220163633 -2.501918872628857e-017 -0.9238795325109536 -0.382683432365894 -6.687388031538348e-018 -0.9238795325109536 -0.382683432365894 -6.687388031538348e-018 -1 -1.274856552025012e-033 -1.95818153218181e-017 -1 -1.274856552025012e-033 -1.95818153218181e-017 -1 -1.274856552025012e-033 -1.95818153218181e-017 -1 -1.274856552025012e-033 -1.95818153218181e-017 -0.9659258262890079 -0.2588190451027462 -1.120185200800945e-017 -0.9659258262890079 -0.2588190451027462 -1.120185200800945e-017 -0.9978589232385796 -0.0654031292305077 -1.759089571435819e-017 -0.9914448613738123 -0.130526192220036 -1.552464919086907e-017 -0.9914448613738123 -0.130526192220036 -1.552464919086907e-017 -0.9978589232385796 -0.0654031292305077 -1.759089571435819e-017 + + + + + + + + + + + + + + +

0 1 2 1 0 3 4 5 6 5 4 7 8 3 0 3 8 9 10 11 12 11 10 13 14 9 8 9 14 15 12 16 17 16 12 11 18 15 14 15 18 19 17 20 21 20 17 16 22 19 18 19 22 23 21 24 25 24 21 20 26 23 22 23 26 27 25 28 29 28 25 24 30 26 31 26 30 27 29 32 33 32 29 28 34 31 35 31 34 30 32 36 33 36 32 37 38 35 39 35 38 34 37 40 36 40 37 41 42 39 43 39 42 38 41 44 40 44 41 45 46 43 47 43 46 42 45 48 44 48 45 49 50 47 51 47 50 46 49 52 48 52 49 53 54 55 56 55 54 57 53 58 52 58 53 59 60 61 62 61 60 63 64 65 66 65 64 67 68 62 69 62 68 60 70 71 72 71 70 73 74 69 75 69 74 68 73 76 71 76 73 77 78 75 79 75 78 74 77 80 76 80 77 81 82 79 83 79 82 78 81 84 80 84 81 85 82 86 87 86 82 83 85 88 84 88 85 89 87 90 91 90 87 86 89 92 88 92 89 93 91 94 95 94 91 90 96 92 93 92 96 97 95 98 99 98 95 94 100 97 96 97 100 101 99 102 103 102 99 98 104 101 100 101 104 105 106 107 108 107 106 109 110 105 104 105 110 111 112 113 114 113 112 115 114 111 110 111 114 113

+
+
+
+ + + + 0 0 2.165354330708662 0.1184986753859656 0.2465682045726894 2.165354330708662 0 7.874015748031497 2.165354330708662 0.119594327961949 0.2298517765885317 2.165354330708662 0.1228625387705518 0.2134213713218521 2.165354330708662 0.1282473878187189 0.1975581175621329 2.165354330708662 0.1356567388462747 0.1825334399793274 2.165354330708662 0.1449638158028776 0.1686044149725052 2.165354330708662 0.1560093720213896 0.1560093720213882 2.165354330708662 0.1686044149725068 0.1449638158028763 2.165354330708662 0.1825334399793289 0.1356567388462739 2.165354330708662 0.197558117562134 0.1282473878187185 2.165354330708662 0.2134213713218537 0.1228625387705514 2.165354330708662 0.2298517765885331 0.1195943279619491 2.165354330708662 0.2465682045726913 0.1184986753859656 2.165354330708662 51.18110236220473 0 2.165354330708662 30.0860261920037 0.1184986753859688 2.165354330708662 30.09803909744245 0.1212016043046447 2.165354330708662 30.70679771243117 0.1184986753859656 2.165354330708662 30.10330938016302 0.1244567554178949 2.165354330708662 30.10773656538716 0.1287894127682915 2.165354330708662 30.11110468898 0.1339882234195986 2.165354330708662 30.11324944927784 0.1397995822959414 2.165354330708662 30.11406622194742 0.145940003383379 2.165354330708662 51.06260368681876 0.1184986753859656 2.165354330708662 51.06260368681876 7.755517072645532 2.165354330708662 0.1184986753859656 7.755517072645532 2.165354330708662 51.18110236220473 7.874015748031497 2.165354330708662 0.1184986753859656 2.43930318405221 2.165354330708662 0.1184986753859656 2.804370064010866 2.165354330708662 0.1195943279619488 2.456019612036368 2.165354330708662 0.1228625387705512 2.472450017303047 2.165354330708662 0.1282473878187184 2.488313271062767 2.165354330708662 0.1356567388462739 2.503337948645572 2.165354330708662 0.1449638158028762 2.517266973652394 2.165354330708662 0.1560093720213884 2.529862016603511 2.165354330708662 0.1686044149725052 2.540907572822023 2.165354330708662 0.1825334399793273 2.550214649778626 2.165354330708662 0.1975581175621327 2.557624000806182 2.165354330708662 0.213421371321852 2.563008849854349 2.165354330708662 0.2298517765885315 2.566277060662952 2.165354330708662 0.2465682045726894 2.567372713238935 2.165354330708662 25.61991398185795 2.804370064010866 2.165354330708662 25.56118838034679 2.567372713238936 2.165354330708662 30.09912146437194 0.1713469183847506 2.165354330708662 30.10848249331568 0.1633477397435226 2.165354330708662 30.11162315591949 0.1580084394959358 2.165354330708662 30.11351516370367 0.1521099485644012 2.165354330708662 0 7.874015748031497 2.165354330708662 0 0 0 0 0 2.165354330708662 0 7.874015748031497 0 51.18110236220473 0 2.165354330708662 0 0 0 51.18110236220473 0 0 0 0 2.165354330708662 51.18110236220473 0 0 51.18110236220473 0.7153153851313135 0.604869657207319 51.18110236220473 0 2.165354330708662 51.18110236220473 7.874015748031497 0 51.18110236220473 7.182685229005588 0.604869657207319 51.18110236220473 0.7153153851313138 1.166727690057971 51.18110236220473 7.874015748031497 2.165354330708662 51.18110236220473 7.182685229005587 1.166727690057971 0 7.874015748031497 2.165354330708662 51.18110236220473 7.874015748031497 0 0 7.874015748031497 0 51.18110236220473 7.874015748031497 2.165354330708662 0 7.874015748031497 0 0.346039204183232 7.209720004747907 1.256040330056125e-015 0 0 0 0.3542852686363268 7.272355082731298 1.256040330056125e-015 0.3784615063303982 7.330721683659481 1.256040330056125e-015 0.4169203466197171 7.380842220134569 1.256040330056125e-015 0.4670408830948051 7.419301060423888 1.256040330056125e-015 0.525407484022988 7.443477298117959 1.256040330056125e-015 0.5880425620063782 7.451723362571054 1.256040330056125e-015 51.18110236220473 7.874015748031497 0 0.3460392041832313 0.5491086559751139 1.110223024625157e-015 0.3460392041832319 2.136762732649793 1.110223024625157e-015 0.6506776399897686 7.443477298117959 1.256040330056125e-015 0.7090442409179513 7.419301060423888 1.256040330056125e-015 0.7591647773930393 7.380842220134569 1.256040330056125e-015 0.7976236176823582 7.330721683659481 1.256040330056125e-015 0.8217998553764297 7.272355082731298 1.256040330056125e-015 0.8300459198295244 7.209720004747907 1.256040330056125e-015 43.55364811608248 7.569833598791506 8.326672684688674e-016 0.8300459198295258 3.173087089051805 5.549316253182147e-016 43.52759575677882 7.56465146232659 8.326672684688674e-016 25.50480608586854 2.339832184441669 1.110223024625157e-015 43.50244268356087 7.556113144499255 8.326672684688674e-016 43.47861927248514 7.544364738294798 8.326672684688674e-016 43.45653314872024 7.529607262200647 8.326672684688674e-016 43.43656221196721 7.512093220724323 8.326672684688674e-016 43.41904817049088 7.492122283971291 8.326672684688674e-016 43.40429069439674 7.470036160206389 8.326672684688674e-016 43.39254228819227 7.446212749130662 8.326672684688674e-016 43.38400397036494 7.421059675912715 8.326672684688674e-016 43.37882183390003 7.395007316609055 8.326672684688674e-016 50.144256319116 7.569833598791506 1.090510587941475e-015 50.1707622014146 7.568096311480678 1.090510587941475e-015 50.19681456071828 7.562914175015767 1.090510587941475e-015 50.22196763393622 7.554375857188427 1.090510587941475e-015 50.24579104501194 7.542627450983966 1.090510587941475e-015 50.26787716877683 7.527869974889834 1.090510587941475e-015 50.28784810552988 7.510355933413502 1.090510587941475e-015 50.3053621470062 7.490384996660477 1.090510587941475e-015 50.32011962310036 7.468298872895575 1.118266163557104e-015 50.3318680293048 7.44447546181984 1.118266163557104e-015 50.34040634713218 7.419322388601879 1.118266163557104e-015 50.34558848359706 7.393270029298235 1.118266163557104e-015 50.3473257709079 7.366764146999632 1.118266163557104e-015 50.3473257709079 3.127233759244805 1.103017739216966e-015 50.3473257709079 2.136762732649773 1.110223024625157e-015 50.3473257709079 0.5508869384357039 1.110223024625157e-015 0.5491086559751147 0.346039204183232 1.110223024625157e-015 51.18110236220473 0 0 0.5226027736765072 0.3477764914940557 1.110223024625157e-015 0.4965504143728469 0.3529586279589738 1.110223024625157e-015 0.4713973411549005 0.3614969457863064 1.110223024625157e-015 0.4475739300791731 0.3732453519907652 1.110223024625157e-015 0.4254878063142707 0.3880028280849154 1.110223024625157e-015 0.4055168695612388 0.4055168695612393 1.110223024625157e-015 0.3880028280849136 0.4254878063142707 1.110223024625157e-015 0.3732453519907644 0.4475739300791728 1.110223024625157e-015 0.361496945786306 0.4713973411548998 1.110223024625157e-015 0.352958627958972 0.4965504143728474 1.110223024625157e-015 0.3477764914940549 0.5226027736765067 1.110223024625157e-015 28.98669970978262 0.3460392041831966 1.110223024625157e-015 29.00270410638306 0.3478174866438403 1.110223024625157e-015 50.14425631911605 0.3478174866438403 1.110223024625157e-015 50.17076220141466 0.3495547739546495 1.110223024625157e-015 50.19681456071831 0.35473691041958 1.110223024625157e-015 50.22196763393623 0.3632752282469015 1.110223024625157e-015 50.24579104501201 0.3750236344513794 1.110223024625157e-015 50.26787716877686 0.3897811105455421 1.110223024625157e-015 50.28784810552991 0.407295152021843 1.110223024625157e-015 50.30536214700624 0.4272660887748815 1.110223024625157e-015 50.32011962310041 0.4493522125397739 1.110223024625157e-015 50.33186802930485 0.4731756236154915 1.110223024625157e-015 50.3404063471322 0.498328696833425 1.110223024625157e-015 50.34558848359711 0.5243810561371139 1.110223024625157e-015 43.55538540339332 2.925901594763743 1.109463768595622e-015 50.14425631911605 2.339832184441669 1.110223024625157e-015 43.52933304408965 2.931083731228659 1.109462778393509e-015 43.5041799708717 2.939622049055988 1.109231021428294e-015 43.480356559796 2.951370455260453 1.108772463125903e-015 43.45827043603106 2.96612793135459 1.108094949546031e-015 43.43829949927805 2.98364197283092 1.107210073133866e-015 43.42078545780171 3.003612909583954 1.106132974370159e-015 43.4060279817076 3.025699033348864 1.104882082713383e-015 43.39427957550313 3.04952244442458 1.1034788012666e-015 43.38574125767577 3.074675517642528 1.101947140564425e-015 43.38055912121086 3.10072787694619 1.100313307746131e-015 43.37882183390003 3.127233759244795 1.098605258144222e-015 43.58189128569192 2.924164307452924 1.109233975091996e-015 50.14425631911599 2.924164307452924 1.117398622990049e-015 50.17076220141464 2.925901594763754 1.118280362204888e-015 50.17076220141468 2.338094897130827 1.110223024625157e-015 50.19681456071832 2.931083731228657 1.118760003154504e-015 50.19681456071832 2.332912760665919 1.110223024625157e-015 50.22196763393622 2.939622049056019 1.118829339049262e-015 50.22196763393626 2.324374442838587 1.110223024625157e-015 50.24579104501196 2.951370455260466 1.11848718353279e-015 50.24579104501199 2.312626036634129 1.110223024625157e-015 50.26787716877688 2.966127931354595 1.11773939098083e-015 50.26787716877689 2.297868560539985 1.110223024625157e-015 50.28784810552991 2.98364197283095 1.116598756331273e-015 50.28784810552993 2.280354519063654 1.110223024625157e-015 50.3053621470062 3.003612909583975 1.115084796159225e-015 50.30536214700626 2.260383582310614 1.110223024625157e-015 50.32011962310035 3.025699033348873 1.113223414742969e-015 50.32011962310039 2.238297458545719 1.110223024625157e-015 50.33186802930481 3.049522444424608 1.111046460834616e-015 50.33186802930484 2.214474047469999 1.110223024625157e-015 50.34040634713214 3.074675517642548 1.108591182719098e-015 50.34040634713219 2.189320974252057 1.110223024625157e-015 50.34558848359704 3.100727876946217 1.105899590885709e-015 50.34558848359709 2.163268614948385 1.110223024625157e-015 0.3460392041832334 3.173087089051805 5.549316253182147e-016 0.3477764914940558 2.163268614948401 1.110223024625157e-015 0.354285268636328 3.110452011068415 5.549316253182147e-016 0.3529586279589722 2.189320974252061 1.110223024625157e-015 0.3614969457863068 2.214474047470008 1.110223024625157e-015 0.3784615063303993 3.052085410140232 5.549316253182147e-016 0.3732453519907648 2.238297458545735 1.110223024625157e-015 0.3880028280849145 2.260383582310638 1.110223024625157e-015 0.4169203466197183 3.001964873665144 5.549316253182147e-016 0.4055168695612396 2.280354519063669 1.110223024625157e-015 0.4254878063142705 2.297868560539994 1.110223024625157e-015 0.4670408830948064 2.963506033375825 5.549316253182147e-016 0.4475739300791732 2.312626036634144 1.110223024625157e-015 0.4713973411548998 2.324374442838602 1.110223024625157e-015 0.525407484022989 2.939329795681753 5.549316253182147e-016 0.4965504143728471 2.332912760665936 1.110223024625157e-015 0.5226027736765068 2.338094897130853 1.110223024625157e-015 0.5491086559751146 2.339832184441677 1.110223024625157e-015 0.5880425620063796 2.931083731228659 5.549316253182147e-016 0.6506776399897698 2.939329795681753 5.549316253182147e-016 0.7090442409179527 2.963506033375825 5.549316253182147e-016 0.7591647773930408 3.001964873665144 5.549316253182147e-016 0.7976236176823597 3.052085410140232 5.549316253182147e-016 0.8217998553764312 3.110452011068415 5.549316253182147e-016 + + + + + + + + + + 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 -1 0 0 -1 0 0 -1 0 0 -1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 -0 1 0 -0 1 0 -0 1 0 -0 1 0 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 0 0 -1 + + + + + + + + + + + + + + +

0 1 2 1 0 3 3 0 4 4 0 5 5 0 6 6 0 7 7 0 8 8 0 9 9 0 10 10 0 11 11 0 12 12 0 13 13 0 14 14 0 15 14 15 16 16 15 17 17 15 18 17 18 19 19 18 20 20 18 21 21 18 22 22 18 23 18 15 24 24 15 25 2 26 27 26 2 1 26 1 28 26 28 29 27 26 25 27 25 15 30 29 28 29 30 31 29 31 32 29 32 33 29 33 34 29 34 35 29 35 36 29 36 37 29 37 38 29 38 39 29 39 40 29 40 41 29 41 42 42 41 43 42 43 44 42 44 18 18 44 45 18 45 46 18 46 47 18 47 23 48 49 50 49 48 51 52 53 54 53 52 55 56 57 58 57 56 59 57 59 60 58 61 62 61 58 57 62 61 63 62 63 60 62 60 59 64 65 66 65 64 67 68 69 70 69 68 71 71 68 72 72 68 73 73 68 74 74 68 75 75 68 76 76 68 77 70 69 78 78 69 79 76 77 80 80 77 81 81 77 82 82 77 83 83 77 84 84 77 85 85 77 86 85 86 87 87 86 88 87 88 89 89 88 90 89 90 91 89 91 92 89 92 93 89 93 94 89 94 95 89 95 96 89 96 97 89 97 98 86 77 99 99 77 100 100 77 101 101 77 102 102 77 103 103 77 104 104 77 105 105 77 106 106 77 107 107 77 108 108 77 109 109 77 110 110 77 111 111 77 112 112 77 113 113 77 114 70 115 116 115 70 117 117 70 118 118 70 119 119 70 120 120 70 121 121 70 122 122 70 123 123 70 124 124 70 125 125 70 126 126 70 127 127 70 78 116 115 128 116 128 129 116 129 130 116 130 131 116 131 132 116 132 133 116 133 134 116 134 135 116 135 136 116 136 137 116 137 138 116 138 139 116 139 140 116 140 141 116 141 114 116 114 77 89 142 143 142 89 144 144 89 145 145 89 146 146 89 147 147 89 148 148 89 149 149 89 150 150 89 151 151 89 152 152 89 153 153 89 154 154 89 98 143 142 155 143 155 156 143 156 157 143 157 158 158 157 159 158 159 160 160 159 161 160 161 162 162 161 163 162 163 164 164 163 165 164 165 166 166 165 167 166 167 168 168 167 169 168 169 170 170 169 171 170 171 172 172 171 173 172 173 174 174 173 175 174 175 176 176 175 177 176 177 178 178 177 112 178 112 113 179 180 79 180 179 181 180 181 182 182 181 183 183 181 184 183 184 185 185 184 186 186 184 187 186 187 188 188 187 189 189 187 190 189 190 191 191 190 192 192 190 193 192 193 194 194 193 195 195 193 196 196 193 197 196 197 89 89 197 198 89 198 199 89 199 200 89 200 201 89 201 202 89 202 87 179 79 69

+
+
+
+ + + + 0.6470483783510791 7.225530565586209 -0.2337572933700505 0.590059644476194 7.209179529129053 -0.2420033578231444 0.5880425620063792 7.209720004747907 -0.2417307881423126 0.6506776399897661 7.197963586567997 -0.2337572933700505 0.5880425620063748 7.193858266663263 -0.2420033578231444 0.7039126674564964 7.240767305930175 -0.209581055675979 0.7090442409179504 7.201789135705585 -0.209581055675979 0.5880425620063785 3.188948827136449 -0.2420033578231452 0.6506776399897699 3.184843507231715 -0.2337572933700513 0.7090442409179538 3.181017958094126 -0.2095810556759798 0.6919288565104798 7.269698784844964 -0.209581055675979 0.6409457296562897 7.240263662831568 -0.2337572933700505 0.752743139522957 7.253851391486414 -0.1711222153866596 0.7591647773930373 7.205074209224319 -0.1711222153866596 0.5900596444761919 3.173627564670658 -0.2420033578231452 0.6470483783510829 3.157276528213503 -0.2337572933700513 0.5880425620063792 3.173087089051805 -0.2417307881423139 0.5254074840229897 7.197963586567996 -0.2337572933700505 0.5880425620063785 3.188948827136449 -0.2420033578231452 0.5254074840229894 3.184843507231715 -0.2337572933700513 0.5880425620063748 7.193858266663263 -0.2420033578231444 0.7039126674564999 3.142039787869536 -0.2095810556759798 0.7591647773930392 3.177732884575392 -0.1711222153866604 0.6728653662742286 7.294542809015757 -0.209581055675979 0.631237817512777 7.252915260254307 -0.2337572933700505 0.7357090600596556 7.294975297149257 -0.1711222153866596 0.7976236176823564 7.20759493479274 -0.121001678911572 0.7902120785753058 7.263891163446743 -0.121001678911572 0.5290367456616765 3.157276528213502 -0.2337572933700513 0.5860254795365677 3.173627564670658 -0.2420033578231452 0.5880425620063792 3.173087089051805 -0.2417307881423139 0.4670408830948055 3.181017958094127 -0.2095810556759798 0.4670408830948049 7.201789135705584 -0.209581055675979 0.5880425620063792 7.209720004747907 -0.2417307881423126 0.5860254795365617 7.209179529129052 -0.2420033578231444 0.5290367456616767 7.225530565586209 -0.2337572933700505 0.6919288565104833 3.113108308954748 -0.2095810556759798 0.6409457296562934 3.142543430968143 -0.2337572933700513 0.7527431395229589 3.128955702313299 -0.1711222153866604 0.7976236176823581 3.175212159006971 -0.1210016789115728 0.6480213421034335 7.313606299252011 -0.209581055675979 0.6185862200900375 7.26262317239782 -0.2337572933700505 0.7086117527844502 7.33028919552598 -0.1711222153866596 0.7693027917821517 7.314370647202324 -0.121001678911572 0.8217998553764282 7.209179529129053 -0.06263507798338919 0.8137660383374742 7.270202427943571 -0.06263507798338919 0.4721724565562595 3.142039787869536 -0.2095810556759798 0.4169203466197199 3.177732884575392 -0.1711222153866604 0.4169203466197176 7.205074209224319 -0.1711222153866596 0.4721724565562592 7.240767305930176 -0.209581055675979 0.6728653662742311 3.088264284783953 -0.2095810556759798 0.6312378175127806 3.129891833545404 -0.2337572933700513 0.7357090600596575 3.087831796650455 -0.1711222153866604 0.7902120785753077 3.118915930352971 -0.1210016789115728 0.8217998553764306 3.173627564670658 -0.06263507798339002 0.6190898631886472 7.325590110198027 -0.209581055675979 0.6038531228446804 7.268725821092609 -0.2337572933700505 0.6732978544077269 7.357386502801186 -0.1711222153866596 0.7360409198764716 7.357718362618001 -0.121001678911572 0.790420694377345 7.326563073950379 -0.06263507798338919 0.8300459198295244 7.209720004747907 1.256040330056125e-015 0.8217998553764297 7.272355082731298 1.256040330056125e-015 0.4841562675022759 3.113108308954748 -0.2095810556759798 0.5351393943564656 3.142543430968144 -0.2337572933700513 0.4233419844898002 3.128955702313298 -0.1711222153866604 0.3784615063303992 7.207594934792739 -0.121001678911572 0.3784615063304005 3.175212159006972 -0.1210016789115728 0.4233419844897982 7.253851391486415 -0.1711222153866596 0.4841562675022756 7.269698784844964 -0.209581055675979 0.5351393943564662 7.240263662831568 -0.2337572933700505 0.6480213421034365 3.069200794547701 -0.2095810556759798 0.6185862200900409 3.120183921401891 -0.2337572933700513 0.7086117527844518 3.052517898273733 -0.1711222153866604 0.7693027917821532 3.068436446597388 -0.1210016789115728 0.8137660383374767 3.112604665856142 -0.06263507798339002 0.8300459198295258 3.173087089051805 5.549316253182147e-016 0.5880425620063783 7.329677564942021 -0.209581055675979 0.5880425620063781 7.270807320915229 -0.2337572933700505 0.6321739487448852 7.374420582264487 -0.1711222153866596 0.6926932044607942 7.390980234523682 -0.121001678911572 0.753283615141812 7.37496105788334 -0.06263507798338919 0.7976236176823582 7.330721683659481 1.256040330056125e-015 0.5032197577385278 3.088264284783953 -0.2095810556759798 0.5448473064999787 3.129891833545404 -0.2337572933700513 0.4403760639531013 3.087831796650455 -0.1711222153866604 0.3858730454374511 3.11891593035297 -0.1210016789115728 0.3542852686363288 7.209179529129052 -0.06263507798338919 0.3542852686363288 3.173627564670658 -0.06263507798339002 0.3858730454374499 7.263891163446743 -0.121001678911572 0.4403760639530996 7.294975297149258 -0.1711222153866596 0.5032197577385272 7.294542809015758 -0.209581055675979 0.5448473064999786 7.252915260254307 -0.2337572933700505 0.6190898631886485 3.057216983601685 -0.2095810556759798 0.6038531228446821 3.114081272707101 -0.2337572933700513 0.6732978544077288 3.025420590998527 -0.1711222153866604 0.7360409198764732 3.025088731181712 -0.1210016789115728 0.7904206943773474 3.056244019849333 -0.06263507798339002 0.8217998553764312 3.110452011068415 5.549316253182147e-016 0.5722320011680755 7.268725821092609 -0.2337572933700505 0.5569952608241093 7.325590110198028 -0.209581055675979 0.5880425620063781 7.380230589550607 -0.1711222153866596 0.6422137207052132 7.411889521316836 -0.121001678911572 0.7048856312088494 7.412098137118874 -0.06263507798338919 0.7591647773930393 7.380842220134569 1.256040330056125e-015 0.5280637819093225 3.069200794547701 -0.2095810556759798 0.5574989039227182 3.120183921401891 -0.2337572933700513 0.467473371228307 3.052517898273733 -0.1711222153866604 0.4067823322306052 3.068436446597388 -0.1210016789115728 0.3623190856752828 3.112604665856142 -0.06263507798339002 0.346039204183232 7.209720004747907 1.256040330056125e-015 0.3460392041832334 3.173087089051805 5.549316253182147e-016 0.3623190856752829 7.27020242794357 -0.06263507798338919 0.406782332230604 7.314370647202324 -0.121001678911572 0.4674733712283056 7.330289195525981 -0.1711222153866596 0.5280637819093215 7.313606299252011 -0.209581055675979 0.5574989039227177 7.26262317239782 -0.2337572933700505 0.5880425620063796 3.111999772884482 -0.2337572933700513 0.5880425620063795 3.05312952885769 -0.2095810556759798 0.6321739487448865 3.008386511535226 -0.1711222153866604 0.692693204460796 2.991826859276031 -0.1210016789115728 0.7532836151418134 3.007846035916371 -0.06263507798339002 0.7976236176823597 3.052085410140232 5.549316253182147e-016 0.5439111752678711 7.374420582264487 -0.1711222153866596 0.5880425620063783 7.41902128965674 -0.121001678911572 0.6485249852020408 7.435443481079003 -0.06263507798338919 0.7090442409179513 7.419301060423888 1.256040330056125e-015 0.5569952608241104 3.057216983601685 -0.2095810556759798 0.5722320011680768 3.114081272707101 -0.2337572933700513 0.5027872696050301 3.025420590998527 -0.1711222153866604 0.4400442041362855 3.025088731181712 -0.1210016789115728 0.3856644296354121 3.056244019849333 -0.06263507798339002 0.354285268636328 3.110452011068415 5.549316253182147e-016 0.3542852686363268 7.272355082731298 1.256040330056125e-015 0.385664429635412 7.326563073950378 -0.06263507798338919 0.4400442041362841 7.357718362618001 -0.121001678911572 0.5027872696050288 7.357386502801186 -0.1711222153866596 0.5880425620063796 3.002576504249106 -0.1711222153866604 0.6422137207052142 2.970917572482877 -0.1210016789115728 0.7048856312088514 2.970708956680837 -0.06263507798339002 0.7591647773930408 3.001964873665144 5.549316253182147e-016 0.5338714033075435 7.411889521316836 -0.121001678911572 0.5880425620063782 7.443406143152849 -0.06263507798338919 0.6506776399897686 7.443477298117959 1.256040330056125e-015 0.5439111752678723 3.008386511535226 -0.1711222153866604 0.4833919195519629 2.991826859276031 -0.1210016789115728 0.4228015088709456 3.007846035916372 -0.06263507798339002 0.3784615063303993 3.052085410140232 5.549316253182147e-016 0.3784615063303982 7.330721683659481 1.256040330056125e-015 0.4228015088709459 7.374961057883341 -0.06263507798338919 0.4833919195519614 7.390980234523682 -0.121001678911572 0.5880425620063796 2.963785804142972 -0.1210016789115728 0.6485249852020425 2.947363612720708 -0.06263507798339002 0.7090442409179527 2.963506033375825 5.549316253182147e-016 0.5275601388107158 7.435443481079003 -0.06263507798338919 0.5880425620063782 7.451723362571054 1.256040330056125e-015 0.5338714033075445 2.970917572482877 -0.1210016789115728 0.4711994928039077 2.970708956680837 -0.06263507798339002 0.4169203466197183 3.001964873665144 5.549316253182147e-016 0.4169203466197171 7.380842220134569 1.256040330056125e-015 0.4711994928039074 7.412098137118874 -0.06263507798338919 0.5880425620063796 2.939400950646861 -0.06263507798339002 0.6506776399897698 2.939329795681753 5.549316253182147e-016 0.525407484022988 7.443477298117959 1.256040330056125e-015 0.5275601388107163 2.947363612720708 -0.06263507798339002 0.4670408830948064 2.963506033375825 5.549316253182147e-016 0.4670408830948051 7.419301060423888 1.256040330056125e-015 0.5880425620063796 2.931083731228659 5.549316253182147e-016 0.525407484022989 2.939329795681753 5.549316253182147e-016 + + + + + + + + + + 0.2980469559637359 0.07455112482027697 -0.9516355089154578 0.129409522551249 0.01703708685546249 -0.9914448613738121 0.129409522551249 0.01703708685546249 -0.9914448613738121 0.2628076869683011 0.01722532585836539 -0.9646944634543336 0.1300206976615136 0.007784386697886409 -0.9914807217003017 0.487749567089461 0.1306921026102494 -0.8631453725296541 0.5022026247522211 0.03291609906116259 -0.8641232864091647 0.1300206976615145 -0.007784386697885729 -0.9914807217003016 0.2628076869683022 -0.01722532585836404 -0.9646944634543334 0.5022026247522249 -0.03291609906116251 -0.8641232864091626 0.4373042984129965 0.2524777544065234 -0.8631453725296547 0.3289889588963535 0.189941863979224 -0.925034244356603 0.6853829641193342 0.1836478117418226 -0.704644359757059 0.7075597098930087 0.04637591353493291 -0.7051301522271769 0.1294095225512511 -0.01703708685545926 -0.9914448613738118 0.2980469559637368 -0.07455112482027632 -0.9516355089154577 0.1294095225512511 -0.01703708685545926 -0.9914448613738118 -0.2628076869683021 0.01722532585836941 -0.9646944634543332 -0.1300206976615204 -0.007784386697888517 -0.9914807217003007 -0.2628076869683041 -0.01722532585836543 -0.9646944634543327 -0.1300206976615192 0.007784386697895602 -0.9914807217003009 0.4877495670894685 -0.1306921026102526 -0.8631453725296494 0.7075597098930115 -0.04637591353493292 -0.7051301522271741 0.3570574644792096 0.3570574644792076 -0.8631453725296554 0.2686183601018445 0.2686183601018439 -0.9250342443566033 0.6144975546712324 0.3547803286058008 -0.7046443597570592 0.8650724726254417 0.05669984544201129 -0.4984322869082181 0.8373882722621905 0.2243775113039457 -0.4984331589077831 -0.2980469559637379 -0.07455112482027781 -0.951635508915457 -0.1294095225512526 -0.01703708685546406 -0.9914448613738116 -0.1294095225512526 -0.01703708685546406 -0.9914448613738116 -0.5022026247522233 -0.03291609906116239 -0.8641232864091635 -0.5022026247522188 0.03291609906116216 -0.8641232864091661 -0.1294095225512497 0.0170370868554802 -0.9914448613738116 -0.1294095225512497 0.0170370868554802 -0.9914448613738116 -0.2980469559637334 0.07455112482028185 -0.9516355089154581 0.4373042984130039 -0.2524777544065295 -0.8631453725296491 0.328988958896355 -0.1899418639792258 -0.9250342443566021 0.6853829641193395 -0.1836478117418259 -0.7046443597570529 0.8650724726254407 -0.05669984544201203 -0.4984322869082199 0.2524777544065273 0.4373042984129941 -0.8631453725296547 0.1899418639792284 0.3289889588963501 -0.9250342443566034 0.5017351523775112 0.5017351523775082 -0.7046443597570581 0.7507817855914651 0.4334640660138978 -0.4984331589077823 0.9640854128455839 0.06318949640755746 -0.2579658975177134 0.9331937336188315 0.2500485073049494 -0.2581185764897834 -0.4877495670894679 -0.1306921026102518 -0.8631453725296499 -0.7075597098930101 -0.0463759135349334 -0.7051301522271755 -0.7075597098930094 0.04637591353493286 -0.7051301522271762 -0.4877495670894583 0.1306921026102496 -0.8631453725296557 0.3570574644792161 -0.3570574644792161 -0.8631453725296491 0.2686183601018471 -0.2686183601018466 -0.9250342443566016 0.6144975546712366 -0.3547803286058063 -0.7046443597570529 0.8373882722621882 -0.2243775113039466 -0.4984331589077866 0.9640854128455844 -0.06318949640755783 -0.2579658975177117 0.1306921026102529 0.4877495670894601 -0.8631453725296541 0.09832114372019474 0.3669395038220337 -0.9250342443566036 0.3547803286058044 0.6144975546712306 -0.704644359757059 0.6130107609582474 0.6130107609582429 -0.4984331589077781 0.8366786123435727 0.4830566220617641 -0.2581185764897827 0.9892858993695024 0.06484122355896389 -0.1308014718420683 0.9575208326510117 0.2565669338448132 -0.1316330638433379 -0.4373042984130037 -0.2524777544065278 -0.8631453725296495 -0.328988958896355 -0.1899418639792242 -0.9250342443566025 -0.6853829641193372 -0.1836478117418237 -0.7046443597570558 -0.865072472625448 0.05669984544201193 -0.4984322869082074 -0.8650724726254442 -0.05669984544201199 -0.4984322869082139 -0.6853829641193361 0.183647811741824 -0.7046443597570568 -0.437304298412995 0.2524777544065209 -0.8631453725296562 -0.3289889588963511 0.1899418639792211 -0.9250342443566044 0.2524777544065291 -0.4373042984130041 -0.8631453725296492 0.1899418639792263 -0.3289889588963555 -0.925034244356602 0.5017351523775135 -0.5017351523775139 -0.7046443597570524 0.750781785591461 -0.4334640660138997 -0.4984331589077866 0.9331937336188322 -0.2500485073049493 -0.2581185764897809 0.9892858993695034 -0.06484122355896398 -0.1308014718420602 1.481513538301518e-016 0.5049555088130492 -0.8631453725296537 2.833507410527474e-016 0.3798837279584447 -0.9250342443566046 0.1836478117418217 0.6853829641193345 -0.7046443597570591 0.4334640660139029 0.750781785591468 -0.4984331589077735 0.6831452263138832 0.6831452263138795 -0.2581185764897826 0.858489692644828 0.4956492551450112 -0.1316330638433374 -0.3570574644792166 -0.3570574644792146 -0.8631453725296495 -0.268618360101847 -0.2686183601018445 -0.9250342443566024 -0.6144975546712351 -0.3547803286058037 -0.7046443597570554 -0.8373882722621904 -0.2243775113039465 -0.4984331589077828 -0.9640854128455852 0.06318949640755761 -0.2579658975177083 -0.9640854128455854 -0.06318949640755829 -0.2579658975177077 -0.8373882722621981 0.224377511303948 -0.4984331589077693 -0.6144975546712339 0.3547803286058023 -0.7046443597570569 -0.3570574644792097 0.3570574644792061 -0.8631453725296557 -0.2686183601018436 0.2686183601018393 -0.925034244356605 0.130692102610254 -0.4877495670894688 -0.863145372529649 0.09832114372019156 -0.366939503822038 -0.9250342443566022 0.3547803286058064 -0.6144975546712369 -0.7046443597570525 0.6130107609582429 -0.6130107609582404 -0.4984331589077868 0.8366786123435729 -0.4830566220617641 -0.2581185764897814 0.9575208326510132 -0.2565669338448152 -0.1316330638433239 -0.09832114372019248 0.36693950382203 -0.9250342443566053 -0.130692102610252 0.4877495670894637 -0.8631453725296522 -5.095627254616813e-016 0.7095606572116078 -0.7046443597570559 0.2243775113039432 0.8373882722621986 -0.4984331589077709 0.483056622061765 0.8366786123435727 -0.2581185764897807 0.700953898806195 0.7009538988061976 -0.131633063843343 -0.2524777544065299 -0.4373042984130035 -0.8631453725296492 -0.1899418639792275 -0.328988958896354 -0.9250342443566021 -0.5017351523775135 -0.501735152377512 -0.7046443597570538 -0.7507817855914644 -0.4334640660138989 -0.4984331589077828 -0.9331937336188333 -0.2500485073049486 -0.2581185764897773 -0.9892858993695011 0.06484122355896468 -0.1308014718420768 -0.9892858993695026 -0.06484122355896477 -0.1308014718420667 -0.933193733618833 0.2500485073049489 -0.2581185764897785 -0.7507817855914721 0.4334640660139016 -0.4984331589077685 -0.5017351523775114 0.5017351523775091 -0.704644359757057 -0.2524777544065261 0.4373042984129952 -0.8631453725296545 -0.1899418639792249 0.3289889588963474 -0.925034244356605 3.120964684059297e-016 -0.3798837279584495 -0.9250342443566026 1.795773985820026e-016 -0.5049555088130583 -0.8631453725296484 0.1836478117418268 -0.6853829641193396 -0.7046443597570526 0.4334640660138992 -0.7507817855914616 -0.4984331589077862 0.6831452263138821 -0.683145226313881 -0.2581185764897815 0.8584896926448293 -0.4956492551450125 -0.131633063843325 -0.1836478117418218 0.6853829641193373 -0.7046443597570562 2.263559080302044e-017 0.8669281320278058 -0.4984331589077708 0.2500485073049453 0.9331937336188334 -0.2581185764897797 0.4956492551450089 0.8584896926448271 -0.1316330638433521 -0.1306921026102543 -0.4877495670894691 -0.8631453725296487 -0.09832114372019264 -0.3669395038220378 -0.9250342443566023 -0.3547803286058062 -0.6144975546712361 -0.7046443597570532 -0.6130107609582444 -0.613010760958241 -0.4984331589077842 -0.8366786123435742 -0.4830566220617643 -0.258118576489777 -0.9575208326510127 -0.2565669338448145 -0.1316330638433294 -0.9575208326510101 0.2565669338448134 -0.13163306384335 -0.8366786123435743 0.4830566220617635 -0.2581185764897779 -0.6130107609582521 0.6130107609582458 -0.498433158907769 -0.3547803286058033 0.6144975546712327 -0.7046443597570575 3.878087999088903e-016 -0.709560657211612 -0.7046443597570518 0.2243775113039441 -0.8373882722621896 -0.4984331589077854 0.4830566220617642 -0.836678612343573 -0.2581185764897814 0.7009538988061992 -0.7009538988061969 -0.1316330638433243 -0.2243775113039425 0.8373882722621988 -0.4984331589077705 -2.360456869878988e-016 0.966113244123529 -0.2581185764897802 0.2565669338448097 0.9575208326510102 -0.1316330638433568 -0.183647811741826 -0.6853829641193396 -0.7046443597570528 -0.4334640660139001 -0.7507817855914613 -0.4984331589077861 -0.6831452263138839 -0.6831452263138803 -0.2581185764897786 -0.8584896926448302 -0.4956492551450097 -0.1316330638433289 -0.8584896926448269 0.4956492551450096 -0.1316330638433514 -0.6831452263138826 0.6831452263138816 -0.2581185764897779 -0.433464066013904 0.7507817855914699 -0.4984331589077699 4.255491070967834e-016 -0.8669281320277973 -0.4984331589077857 0.2500485073049474 -0.9331937336188324 -0.2581185764897815 0.4956492551450117 -0.8584896926448298 -0.1316330638433249 -0.2500485073049449 0.9331937336188337 -0.2581185764897794 -1.801666719264949e-016 0.9912985102900188 -0.1316330638433572 -0.224377511303944 -0.8373882722621894 -0.4984331589077857 -0.4830566220617651 -0.8366786123435727 -0.2581185764897803 -0.7009538988061994 -0.7009538988061961 -0.1316330638433261 -0.7009538988061964 0.7009538988061944 -0.1316330638433522 -0.4830566220617643 0.8366786123435739 -0.2581185764897782 4.630126937070359e-016 -0.9661132441235285 -0.258118576489782 0.2565669338448128 -0.9575208326510133 -0.1316330638433277 -0.2565669338448093 0.9575208326510102 -0.1316330638433571 -0.2500485073049477 -0.9331937336188324 -0.2581185764897814 -0.4956492551450126 -0.8584896926448291 -0.1316330638433255 -0.4956492551450089 0.8584896926448268 -0.1316330638433547 4.684333470088864e-016 -0.9912985102900226 -0.1316330638433289 -0.2565669338448131 -0.9575208326510133 -0.1316330638433277 + + + + + + + + + + + + + + +

0 1 2 1 3 4 3 1 0 5 3 0 3 5 6 3 7 4 7 3 8 6 8 3 8 6 9 10 0 11 0 10 5 12 6 5 6 12 13 8 14 7 14 8 15 15 16 14 17 18 19 18 17 20 8 21 15 21 8 9 13 9 6 9 13 22 23 11 24 11 23 10 25 5 10 5 25 12 12 26 13 26 12 27 18 28 19 28 18 29 30 28 29 17 31 32 31 17 19 33 34 35 35 20 17 20 35 34 15 36 37 36 15 21 9 38 21 38 9 22 22 26 39 26 22 13 40 24 41 24 40 23 42 10 23 10 42 25 25 27 12 27 25 43 27 44 26 44 27 45 19 46 31 46 19 28 32 47 48 47 32 31 49 17 32 17 49 35 37 50 51 50 37 36 21 52 36 52 21 38 38 39 53 39 38 22 39 44 54 44 39 26 55 41 56 41 55 40 57 23 40 23 57 42 42 43 25 43 42 58 43 45 27 45 43 59 45 60 44 60 45 61 28 62 46 62 28 63 31 64 47 64 31 46 65 47 66 47 65 48 67 32 48 32 67 49 68 35 49 35 68 69 51 70 71 70 51 50 36 72 50 72 36 52 52 53 73 53 52 38 53 54 74 54 53 39 54 60 75 60 54 44 76 56 77 56 76 55 78 40 55 40 78 57 79 42 57 42 79 58 58 59 43 59 58 80 59 61 45 61 59 81 63 82 62 82 63 83 46 84 64 84 46 62 66 64 85 64 66 47 86 66 87 66 86 65 65 67 48 67 65 88 89 49 67 49 89 68 90 69 68 69 90 91 71 92 93 92 71 70 50 94 70 94 50 72 72 73 95 73 72 52 73 74 96 74 73 53 74 75 97 75 74 54 76 98 99 98 76 77 78 76 100 76 78 55 101 57 78 57 101 79 102 58 79 58 102 80 80 81 59 81 80 103 83 104 82 104 83 105 62 106 84 106 62 82 85 84 107 84 85 64 87 85 108 85 87 66 109 87 110 87 109 86 86 88 65 88 86 111 88 89 67 89 88 112 113 68 89 68 113 90 114 91 90 91 114 115 116 92 117 92 116 93 70 118 92 118 70 94 95 94 72 94 95 119 95 96 120 96 95 73 96 97 121 97 96 74 99 115 114 115 99 98 100 99 122 99 100 76 123 78 100 78 123 101 124 79 101 79 124 102 125 80 102 80 125 103 105 126 104 126 105 127 82 128 106 128 82 104 107 106 129 106 107 84 108 107 130 107 108 85 110 108 131 108 110 87 109 111 86 111 109 132 111 112 88 112 111 133 112 113 89 113 112 134 135 90 113 90 135 114 127 117 126 117 127 116 92 136 117 136 92 118 119 118 94 118 119 137 120 119 95 119 120 138 120 121 139 121 120 96 122 114 135 114 122 99 140 100 122 100 140 123 141 101 123 101 141 124 142 102 124 102 142 125 104 143 128 143 104 126 144 106 128 106 144 129 130 129 145 129 130 107 131 130 146 130 131 108 132 133 111 133 132 147 133 134 112 134 133 148 134 135 113 135 134 149 126 136 143 136 126 117 137 136 118 136 137 150 138 137 119 137 138 151 139 138 120 138 139 152 149 122 135 122 149 140 153 123 140 123 153 141 154 124 141 124 154 142 155 128 143 128 155 144 156 129 144 129 156 145 146 145 157 145 146 130 147 148 133 148 147 158 148 149 134 149 148 159 150 143 136 143 150 155 151 150 137 150 151 160 152 151 138 151 152 161 159 140 149 140 159 153 162 141 153 141 162 154 163 144 155 144 163 156 164 145 156 145 164 157 158 159 148 159 158 165 160 155 150 155 160 163 161 160 151 160 161 166 165 153 159 153 165 162 167 156 163 156 167 164 166 163 160 163 166 167

+
+
+
+ + + + 0.1184986753859656 2.804370064010866 2.24409448818898 3.802459269029596 5.211752591652259 2.24409448818898 0.1184986753859656 7.755517072645532 2.24409448818898 3.821449895399476 5.203886416651894 2.24409448818898 5.080260594255362 4.709514930755915 2.24409448818898 5.233106487032441 4.689392387225837 2.24409448818898 25.61991398185795 2.804370064010866 2.24409448818898 3.786151648463726 5.224265869022172 2.24409448818898 3.773638371093813 5.240573489588042 2.24409448818898 3.765772196093449 5.259564115957922 2.24409448818898 3.763089190289438 5.279943568328199 2.24409448818898 3.841829347769753 5.201203410847884 2.24409448818898 3.862208800140031 5.203886416651894 2.24409448818898 4.937830896481261 4.768511243258649 2.24409448818898 3.881199426509911 5.211752591652259 2.24409448818898 3.89750704707578 5.224265869022172 2.24409448818898 3.910020324445693 5.240573489588042 2.24409448818898 3.917886499446058 5.259564115957922 2.24409448818898 3.920569505250068 5.279943568328199 2.24409448818898 4.815523742237236 4.862360823532994 2.24409448818898 4.721674161962891 4.984667977777018 2.24409448818898 4.662677849460157 5.127097675551119 2.24409448818898 4.642555305930079 5.279943568328199 2.24409448818898 5.385952379809521 4.709514930755915 2.24409448818898 5.528382077583623 4.768511243258649 2.24409448818898 5.650689231827647 4.862360823532995 2.24409448818898 5.744538812101991 4.984667977777018 2.24409448818898 5.803535124604726 5.12709767555112 2.24409448818898 5.823657668134803 5.279943568328199 2.24409448818898 5.233106487032441 5.870494749430561 2.24409448818898 51.06260368681876 7.755517072645532 2.24409448818898 5.080260594255362 5.850372205900484 2.24409448818898 3.821449895399476 5.356000720004503 2.24409448818898 3.802459269029596 5.348134545004139 2.24409448818898 3.786151648463726 5.335621267634227 2.24409448818898 3.773638371093813 5.319313647068356 2.24409448818898 3.765772196093449 5.300323020698476 2.24409448818898 3.841829347769753 5.358683725808514 2.24409448818898 3.86220880014003 5.356000720004504 2.24409448818898 4.93783089648126 5.791375893397749 2.24409448818898 3.881199426509911 5.348134545004139 2.24409448818898 3.89750704707578 5.335621267634227 2.24409448818898 3.910020324445693 5.319313647068356 2.24409448818898 3.917886499446058 5.300323020698476 2.24409448818898 4.815523742237236 5.697526313123404 2.24409448818898 4.721674161962891 5.57521915887938 2.24409448818898 4.662677849460157 5.432789461105278 2.24409448818898 5.38595237980952 5.850372205900484 2.24409448818898 5.528382077583622 5.791375893397749 2.24409448818898 5.650689231827647 5.697526313123404 2.24409448818898 5.744538812101991 5.575219158879381 2.24409448818898 5.803535124604726 5.432789461105278 2.24409448818898 30.70679771243117 0.1184986753859656 2.24409448818898 51.06260368681876 0.1184986753859656 2.24409448818898 + + + + + + + + + + -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 + + + + + + + + + + + + + + +

0 1 2 1 0 3 3 0 4 4 0 5 5 0 6 2 1 7 2 7 8 2 8 9 2 9 10 3 4 11 11 4 12 12 4 13 12 13 14 14 13 15 15 13 16 16 13 17 17 13 18 18 13 19 18 19 20 18 20 21 18 21 22 5 6 23 23 6 24 24 6 25 25 6 26 26 6 27 27 6 28 2 29 30 29 2 31 31 2 32 32 2 33 33 2 34 34 2 35 35 2 36 36 2 10 31 32 37 31 37 38 31 38 39 39 38 40 39 40 41 39 41 42 39 42 43 39 43 18 39 18 44 44 18 45 45 18 46 46 18 22 30 29 47 30 47 48 30 48 49 30 49 50 30 50 51 30 51 28 30 28 6 30 6 52 30 52 53

+
+
+
+ + + + 3.765772196093449 5.259564115957922 2.204724409448823 3.765772196093449 5.300323020698476 2.204724409448823 3.763089190289438 5.279943568328199 2.204724409448823 3.773638371093813 5.240573489588042 2.204724409448823 3.773638371093813 5.319313647068356 2.204724409448823 3.786151648463726 5.224265869022172 2.204724409448823 3.786151648463726 5.335621267634227 2.204724409448823 3.802459269029596 5.348134545004139 2.204724409448823 3.802459269029596 5.211752591652259 2.204724409448823 3.821449895399476 5.203886416651894 2.204724409448823 3.821449895399476 5.356000720004503 2.204724409448823 3.841829347769753 5.201203410847884 2.204724409448823 3.841829347769753 5.358683725808514 2.204724409448823 3.862208800140031 5.203886416651894 2.204724409448823 3.86220880014003 5.356000720004504 2.204724409448823 3.881199426509911 5.348134545004139 2.204724409448823 3.881199426509911 5.211752591652259 2.204724409448823 3.89750704707578 5.224265869022172 2.204724409448823 3.89750704707578 5.335621267634227 2.204724409448823 3.910020324445693 5.240573489588042 2.204724409448823 3.910020324445693 5.319313647068356 2.204724409448823 3.917886499446058 5.259564115957922 2.204724409448823 3.917886499446058 5.300323020698476 2.204724409448823 3.920569505250068 5.279943568328199 2.204724409448823 + + + + + + + + + + 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 + + + + + + + + + + + + + + +

0 1 2 1 0 3 1 3 4 4 3 5 4 5 6 6 5 7 7 5 8 7 8 9 7 9 10 10 9 11 10 11 12 12 11 13 12 13 14 14 13 15 15 13 16 15 16 17 15 17 18 18 17 19 18 19 20 20 19 21 20 21 22 22 21 23

+
+
+
+ + + + 3.821449895399476 5.203886416651894 2.24409448818898 3.841829347769753 5.201203410847884 2.204724409448823 3.821449895399476 5.203886416651894 2.204724409448823 3.841829347769753 5.201203410847884 2.24409448818898 3.862208800140031 5.203886416651894 2.204724409448823 3.862208800140031 5.203886416651894 2.24409448818898 3.802459269029596 5.211752591652259 2.24409448818898 3.802459269029596 5.211752591652259 2.204724409448823 3.881199426509911 5.211752591652259 2.204724409448823 3.881199426509911 5.211752591652259 2.24409448818898 3.786151648463726 5.224265869022172 2.24409448818898 3.786151648463726 5.224265869022172 2.204724409448823 3.89750704707578 5.224265869022172 2.204724409448823 3.89750704707578 5.224265869022172 2.24409448818898 3.773638371093813 5.240573489588042 2.204724409448823 3.773638371093813 5.240573489588042 2.24409448818898 3.910020324445693 5.240573489588042 2.24409448818898 3.910020324445693 5.240573489588042 2.204724409448823 3.765772196093449 5.259564115957922 2.204724409448823 3.765772196093449 5.259564115957922 2.24409448818898 3.917886499446058 5.259564115957922 2.24409448818898 3.917886499446058 5.259564115957922 2.204724409448823 3.763089190289438 5.279943568328199 2.204724409448823 3.763089190289438 5.279943568328199 2.24409448818898 3.920569505250068 5.279943568328199 2.24409448818898 3.920569505250068 5.279943568328199 2.204724409448823 3.765772196093449 5.300323020698476 2.204724409448823 3.765772196093449 5.300323020698476 2.24409448818898 3.917886499446058 5.300323020698476 2.24409448818898 3.917886499446058 5.300323020698476 2.204724409448823 3.773638371093813 5.319313647068356 2.204724409448823 3.773638371093813 5.319313647068356 2.24409448818898 3.910020324445693 5.319313647068356 2.24409448818898 3.910020324445693 5.319313647068356 2.204724409448823 3.786151648463726 5.335621267634227 2.204724409448823 3.786151648463726 5.335621267634227 2.24409448818898 3.89750704707578 5.335621267634227 2.24409448818898 3.89750704707578 5.335621267634227 2.204724409448823 3.802459269029596 5.348134545004139 2.24409448818898 3.802459269029596 5.348134545004139 2.204724409448823 3.881199426509911 5.348134545004139 2.204724409448823 3.881199426509911 5.348134545004139 2.24409448818898 3.821449895399476 5.356000720004503 2.24409448818898 3.821449895399476 5.356000720004503 2.204724409448823 3.86220880014003 5.356000720004504 2.204724409448823 3.86220880014003 5.356000720004504 2.24409448818898 3.841829347769753 5.358683725808514 2.24409448818898 3.841829347769753 5.358683725808514 2.204724409448823 + + + + + + + + + + 0.2588190451025272 0.9659258262890665 0 0 0.9999999999999999 0 0.2588190451025272 0.9659258262890665 0 0 0.9999999999999999 0 -0.2588190451025272 0.9659258262890665 0 -0.2588190451025272 0.9659258262890665 0 0.5000000000000094 0.8660254037844333 0 0.5000000000000094 0.8660254037844333 0 -0.5000000000000094 0.8660254037844333 0 -0.5000000000000094 0.8660254037844333 0 0.70710678118654 0.707106781186555 0 0.70710678118654 0.707106781186555 0 -0.70710678118654 0.707106781186555 0 -0.70710678118654 0.707106781186555 0 0.8660254037844379 0.5000000000000012 0 0.8660254037844379 0.5000000000000012 0 -0.8660254037844379 0.5000000000000012 0 -0.8660254037844379 0.5000000000000012 0 0.965925826289069 0.2588190451025184 0 0.965925826289069 0.2588190451025184 0 -0.965925826289069 0.2588190451025184 0 -0.965925826289069 0.2588190451025184 0 1 0 0 1 0 0 -1 0 0 -1 0 0 0.965925826289069 -0.2588190451025184 0 0.965925826289069 -0.2588190451025184 0 -0.965925826289069 -0.2588190451025184 0 -0.965925826289069 -0.2588190451025184 0 0.8660254037844423 -0.499999999999994 0 0.8660254037844423 -0.499999999999994 0 -0.8660254037844379 -0.5000000000000012 0 -0.8660254037844379 -0.5000000000000012 0 0.7071067811865415 -0.7071067811865536 0 0.7071067811865415 -0.7071067811865536 0 -0.70710678118654 -0.707106781186555 0 -0.70710678118654 -0.707106781186555 0 0.4999999999999865 -0.8660254037844466 0 0.4999999999999865 -0.8660254037844466 0 -0.5000000000000059 -0.8660254037844354 0 -0.5000000000000059 -0.8660254037844354 0 0.2588190451025286 -0.9659258262890662 0 0.2588190451025286 -0.9659258262890662 0 -0.2588190451025246 -0.9659258262890673 0 -0.2588190451025246 -0.9659258262890673 0 1.998761949593601e-014 -1 0 1.998761949593601e-014 -1 0 + + + + + + + + + + + + + + +

0 1 2 1 0 3 3 4 1 4 3 5 6 2 7 2 6 0 5 8 4 8 5 9 10 7 11 7 10 6 9 12 8 12 9 13 14 10 11 10 14 15 16 12 13 12 16 17 18 15 14 15 18 19 20 17 16 17 20 21 22 19 18 19 22 23 24 21 20 21 24 25 26 23 22 23 26 27 28 25 24 25 28 29 30 27 26 27 30 31 32 29 28 29 32 33 34 31 30 31 34 35 36 33 32 33 36 37 38 34 39 34 38 35 36 40 37 40 36 41 42 39 43 39 42 38 41 44 40 44 41 45 46 43 47 43 46 42 45 47 44 47 45 46

+
+
+
+ + + + 4.662677849460157 5.127097675551119 1.968503937007879 4.662677849460157 5.432789461105278 1.968503937007879 4.642555305930079 5.279943568328199 1.968503937007879 4.681987464823896 5.279943568328199 1.968503937007879 4.700766390122029 5.137303469262347 1.968503937007879 4.721674161962891 4.984667977777018 1.968503937007879 4.755823413291001 5.004384057223927 1.968503937007879 4.815523742237236 4.862360823532994 1.968503937007879 4.843406489187879 4.890243570483637 1.968503937007879 4.937830896481261 4.768511243258649 1.968503937007879 4.95754697592817 4.802660494586758 1.968503937007879 5.080260594255362 4.709514930755915 1.968503937007879 5.090466387966592 4.747603471417786 1.968503937007879 5.233106487032441 4.689392387225837 1.968503937007879 5.233106487032441 4.728824546119654 1.968503937007879 5.385952379809521 4.709514930755915 1.968503937007879 5.375746586098293 4.747603471417786 1.968503937007879 5.508665998136713 4.802660494586758 1.968503937007879 5.528382077583623 4.768511243258649 1.968503937007879 5.622806484877003 4.890243570483638 1.968503937007879 5.650689231827647 4.862360823532995 1.968503937007879 5.710389560773883 5.004384057223929 1.968503937007879 5.744538812101991 4.984667977777018 1.968503937007879 5.765446583942854 5.137303469262349 1.968503937007879 5.803535124604726 5.12709767555112 1.968503937007879 5.784225509240986 5.279943568328199 1.968503937007879 4.700766390122029 5.422583667394049 1.968503937007879 4.721674161962891 5.57521915887938 1.968503937007879 4.755823413291 5.55550307943247 1.968503937007879 4.815523742237236 5.697526313123404 1.968503937007879 4.843406489187879 5.669643566172761 1.968503937007879 4.93783089648126 5.791375893397749 1.968503937007879 4.95754697592817 5.75722664206964 1.968503937007879 5.080260594255362 5.850372205900484 1.968503937007879 5.090466387966591 5.812283665238612 1.968503937007879 5.233106487032441 5.870494749430561 1.968503937007879 5.233106487032441 5.831062590536744 1.968503937007879 5.375746586098291 5.812283665238612 1.968503937007879 5.38595237980952 5.850372205900484 1.968503937007879 5.508665998136713 5.75722664206964 1.968503937007879 5.528382077583622 5.791375893397749 1.968503937007879 5.622806484877003 5.669643566172761 1.968503937007879 5.650689231827647 5.697526313123404 1.968503937007879 5.710389560773883 5.55550307943247 1.968503937007879 5.744538812101991 5.575219158879381 1.968503937007879 5.765446583942854 5.42258366739405 1.968503937007879 5.803535124604726 5.432789461105278 1.968503937007879 5.823657668134803 5.279943568328199 1.968503937007879 + + + + + + + + + + 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 + + + + + + + + + + + + + + +

0 1 2 1 0 3 3 0 4 4 0 5 4 5 6 6 5 7 6 7 8 8 7 9 8 9 10 10 9 11 10 11 12 12 11 13 12 13 14 14 13 15 14 15 16 16 15 17 17 15 18 17 18 19 19 18 20 19 20 21 21 20 22 21 22 23 23 22 24 23 24 25 1 26 27 26 1 3 27 26 28 27 28 29 29 28 30 29 30 31 31 30 32 31 32 33 33 32 34 33 34 35 35 34 36 35 36 37 35 37 38 38 37 39 38 39 40 40 39 41 40 41 42 42 41 43 42 43 44 44 43 45 44 45 46 46 45 25 46 25 24 46 24 47

+
+
+
+ + + + 4.662677849460157 5.432789461105278 1.968503937007879 4.642555305930079 5.279943568328199 2.24409448818898 4.642555305930079 5.279943568328199 1.968503937007879 4.662677849460157 5.432789461105278 2.24409448818898 4.662677849460157 5.127097675551119 2.24409448818898 4.662677849460157 5.127097675551119 1.968503937007879 4.721674161962891 5.57521915887938 1.968503937007879 4.721674161962891 5.57521915887938 2.24409448818898 4.721674161962891 4.984667977777018 2.24409448818898 4.721674161962891 4.984667977777018 1.968503937007879 4.815523742237236 5.697526313123404 1.968503937007879 4.815523742237236 5.697526313123404 2.24409448818898 4.815523742237236 4.862360823532994 2.24409448818898 4.815523742237236 4.862360823532994 1.968503937007879 4.93783089648126 5.791375893397749 2.24409448818898 4.93783089648126 5.791375893397749 1.968503937007879 4.937830896481261 4.768511243258649 1.968503937007879 4.937830896481261 4.768511243258649 2.24409448818898 5.080260594255362 5.850372205900484 2.24409448818898 5.080260594255362 5.850372205900484 1.968503937007879 5.080260594255362 4.709514930755915 1.968503937007879 5.080260594255362 4.709514930755915 2.24409448818898 5.233106487032441 5.870494749430561 2.24409448818898 5.233106487032441 5.870494749430561 1.968503937007879 5.233106487032441 4.689392387225837 1.968503937007879 5.233106487032441 4.689392387225837 2.24409448818898 5.38595237980952 5.850372205900484 2.24409448818898 5.38595237980952 5.850372205900484 1.968503937007879 5.385952379809521 4.709514930755915 1.968503937007879 5.385952379809521 4.709514930755915 2.24409448818898 5.528382077583622 5.791375893397749 2.24409448818898 5.528382077583622 5.791375893397749 1.968503937007879 5.528382077583623 4.768511243258649 1.968503937007879 5.528382077583623 4.768511243258649 2.24409448818898 5.650689231827647 5.697526313123404 2.24409448818898 5.650689231827647 5.697526313123404 1.968503937007879 5.650689231827647 4.862360823532995 1.968503937007879 5.650689231827647 4.862360823532995 2.24409448818898 5.744538812101991 5.575219158879381 1.968503937007879 5.744538812101991 5.575219158879381 2.24409448818898 5.744538812101991 4.984667977777018 2.24409448818898 5.744538812101991 4.984667977777018 1.968503937007879 5.803535124604726 5.432789461105278 1.968503937007879 5.803535124604726 5.432789461105278 2.24409448818898 5.803535124604726 5.12709767555112 2.24409448818898 5.803535124604726 5.12709767555112 1.968503937007879 5.823657668134803 5.279943568328199 1.968503937007879 5.823657668134803 5.279943568328199 2.24409448818898 + + + + + + + + + + 0.9659258262890681 -0.2588190451025217 0 1 -3.65355505721523e-016 0 1 -3.65355505721523e-016 0 0.9659258262890681 -0.2588190451025217 0 0.9659258262890681 0.2588190451025213 0 0.9659258262890681 0.2588190451025213 0 0.8660254037844393 -0.4999999999999991 0 0.8660254037844393 -0.4999999999999991 0 0.8660254037844384 0.5000000000000006 0 0.8660254037844384 0.5000000000000006 0 0.7071067811865488 -0.7071067811865462 0 0.7071067811865488 -0.7071067811865462 0 0.7071067811865462 0.7071067811865488 0 0.7071067811865462 0.7071067811865488 0 0.4999999999999997 -0.8660254037844389 0 0.4999999999999997 -0.8660254037844389 0 0.4999999999999991 0.8660254037844393 0 0.4999999999999991 0.8660254037844393 0 0.2588190451025206 -0.9659258262890682 0 0.2588190451025206 -0.9659258262890682 0 0.2588190451025217 0.9659258262890681 0 0.2588190451025217 0.9659258262890681 0 0 -1 0 0 -1 0 3.65355505721523e-016 1 0 3.65355505721523e-016 1 0 -0.2588190451025217 -0.9659258262890681 0 -0.2588190451025217 -0.9659258262890681 0 -0.2588190451025213 0.9659258262890681 0 -0.2588190451025213 0.9659258262890681 0 -0.4999999999999991 -0.8660254037844393 0 -0.4999999999999991 -0.8660254037844393 0 -0.5000000000000027 0.8660254037844372 0 -0.5000000000000027 0.8660254037844372 0 -0.7071067811865462 -0.7071067811865488 0 -0.7071067811865462 -0.7071067811865488 0 -0.7071067811865491 0.707106781186546 0 -0.7071067811865491 0.707106781186546 0 -0.8660254037844389 -0.4999999999999997 0 -0.8660254037844389 -0.4999999999999997 0 -0.8660254037844384 0.5000000000000006 0 -0.8660254037844384 0.5000000000000006 0 -0.9659258262890682 -0.2588190451025206 0 -0.9659258262890682 -0.2588190451025206 0 -0.9659258262890681 0.2588190451025217 0 -0.9659258262890681 0.2588190451025217 0 -1 0 0 -1 0 0 + + + + + + + + + + + + + + +

0 1 2 1 0 3 2 4 5 4 2 1 6 3 0 3 6 7 5 8 9 8 5 4 10 7 6 7 10 11 9 12 13 12 9 8 14 10 15 10 14 11 12 16 13 16 12 17 18 15 19 15 18 14 17 20 16 20 17 21 22 19 23 19 22 18 21 24 20 24 21 25 26 23 27 23 26 22 25 28 24 28 25 29 30 27 31 27 30 26 29 32 28 32 29 33 34 31 35 31 34 30 33 36 32 36 33 37 34 38 39 38 34 35 40 36 37 36 40 41 39 42 43 42 39 38 44 41 40 41 44 45 43 46 47 46 43 42 47 45 44 45 47 46

+
+
+
+ + + + 4.700766390122029 5.137303469262347 2.125984251968508 4.700766390122029 5.422583667394049 2.125984251968508 4.681987464823896 5.279943568328199 2.125984251968508 4.755823413291001 5.004384057223927 2.125984251968508 4.755823413291 5.55550307943247 2.125984251968508 4.843406489187879 5.669643566172761 2.125984251968508 4.843406489187879 4.890243570483637 2.125984251968508 4.95754697592817 4.802660494586758 2.125984251968508 4.95754697592817 5.75722664206964 2.125984251968508 5.090466387966592 4.747603471417786 2.125984251968508 5.090466387966591 5.812283665238612 2.125984251968508 5.233106487032441 5.831062590536744 2.125984251968508 5.233106487032441 4.728824546119654 2.125984251968508 5.375746586098293 4.747603471417786 2.125984251968508 5.375746586098291 5.812283665238612 2.125984251968508 5.508665998136713 5.75722664206964 2.125984251968508 5.508665998136713 4.802660494586758 2.125984251968508 5.622806484877003 4.890243570483638 2.125984251968508 5.622806484877003 5.669643566172761 2.125984251968508 5.710389560773883 5.004384057223929 2.125984251968508 5.710389560773883 5.55550307943247 2.125984251968508 5.765446583942854 5.137303469262349 2.125984251968508 5.765446583942854 5.42258366739405 2.125984251968508 5.784225509240986 5.279943568328199 2.125984251968508 + + + + + + + + + + 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 0 0 1 + + + + + + + + + + + + + + +

0 1 2 1 0 3 1 3 4 4 3 5 5 3 6 5 6 7 5 7 8 8 7 9 8 9 10 10 9 11 11 9 12 11 12 13 11 13 14 14 13 15 15 13 16 15 16 17 15 17 18 18 17 19 18 19 20 20 19 21 20 21 22 22 21 23

+
+
+
+ + + + 4.700766390122029 5.137303469262347 2.125984251968508 4.755823413291001 5.004384057223927 1.968503937007879 4.755823413291001 5.004384057223927 2.125984251968508 4.700766390122029 5.137303469262347 1.968503937007879 4.843406489187879 4.890243570483637 1.968503937007879 4.843406489187879 4.890243570483637 2.125984251968508 4.681987464823896 5.279943568328199 2.125984251968508 4.681987464823896 5.279943568328199 1.968503937007879 4.95754697592817 4.802660494586758 2.125984251968508 4.95754697592817 4.802660494586758 1.968503937007879 4.700766390122029 5.422583667394049 2.125984251968508 4.700766390122029 5.422583667394049 1.968503937007879 5.090466387966592 4.747603471417786 2.125984251968508 5.090466387966592 4.747603471417786 1.968503937007879 4.755823413291 5.55550307943247 2.125984251968508 4.755823413291 5.55550307943247 1.968503937007879 5.233106487032441 4.728824546119654 2.125984251968508 5.233106487032441 4.728824546119654 1.968503937007879 4.843406489187879 5.669643566172761 2.125984251968508 4.843406489187879 5.669643566172761 1.968503937007879 5.375746586098293 4.747603471417786 2.125984251968508 5.375746586098293 4.747603471417786 1.968503937007879 4.95754697592817 5.75722664206964 1.968503937007879 4.95754697592817 5.75722664206964 2.125984251968508 5.508665998136713 4.802660494586758 2.125984251968508 5.508665998136713 4.802660494586758 1.968503937007879 5.090466387966591 5.812283665238612 1.968503937007879 5.090466387966591 5.812283665238612 2.125984251968508 5.622806484877003 4.890243570483638 2.125984251968508 5.622806484877003 4.890243570483638 1.968503937007879 5.233106487032441 5.831062590536744 1.968503937007879 5.233106487032441 5.831062590536744 2.125984251968508 5.710389560773883 5.004384057223929 1.968503937007879 5.710389560773883 5.004384057223929 2.125984251968508 5.375746586098291 5.812283665238612 1.968503937007879 5.375746586098291 5.812283665238612 2.125984251968508 5.765446583942854 5.137303469262349 1.968503937007879 5.765446583942854 5.137303469262349 2.125984251968508 5.508665998136713 5.75722664206964 1.968503937007879 5.508665998136713 5.75722664206964 2.125984251968508 5.784225509240986 5.279943568328199 1.968503937007879 5.784225509240986 5.279943568328199 2.125984251968508 5.622806484877003 5.669643566172761 1.968503937007879 5.622806484877003 5.669643566172761 2.125984251968508 5.765446583942854 5.42258366739405 1.968503937007879 5.765446583942854 5.42258366739405 2.125984251968508 5.710389560773883 5.55550307943247 2.125984251968508 5.710389560773883 5.55550307943247 1.968503937007879 + + + + + + + + + + -0.9659258262890681 -0.2588190451025219 0 -0.8660254037844379 -0.500000000000001 0 -0.8660254037844379 -0.500000000000001 0 -0.9659258262890681 -0.2588190451025219 0 -0.707106781186548 -0.7071067811865471 0 -0.707106781186548 -0.7071067811865471 0 -1 7.930887807125743e-016 0 -1 7.930887807125743e-016 0 -0.4999999999999981 -0.8660254037844398 0 -0.4999999999999981 -0.8660254037844398 0 -0.9659258262890688 0.2588190451025187 0 -0.9659258262890688 0.2588190451025187 0 -0.2588190451025187 -0.9659258262890688 0 -0.2588190451025187 -0.9659258262890688 0 -0.8660254037844398 0.4999999999999981 0 -0.8660254037844398 0.4999999999999981 0 -7.930887807125743e-016 -1 0 -7.930887807125743e-016 -1 0 -0.7071067811865475 0.7071067811865475 0 -0.7071067811865475 0.7071067811865475 0 0.2588190451025202 -0.9659258262890684 0 0.2588190451025202 -0.9659258262890684 0 -0.4999999999999992 0.8660254037844393 0 -0.4999999999999992 0.8660254037844393 0 0.5000000000000023 -0.8660254037844374 0 0.5000000000000023 -0.8660254037844374 0 -0.2588190451025195 0.9659258262890687 0 -0.2588190451025195 0.9659258262890687 0 0.7071067811865494 -0.7071067811865457 0 0.7071067811865494 -0.7071067811865457 0 3.920888354084637e-016 1 0 3.920888354084637e-016 1 0 0.8660254037844393 -0.4999999999999992 0 0.8660254037844393 -0.4999999999999992 0 0.2588190451025187 0.9659258262890688 0 0.2588190451025187 0.9659258262890688 0 0.9659258262890687 -0.2588190451025199 0 0.9659258262890687 -0.2588190451025199 0 0.4999999999999981 0.8660254037844398 0 0.4999999999999981 0.8660254037844398 0 1 -3.920888354084637e-016 0 1 -3.920888354084637e-016 0 0.7071067811865475 0.7071067811865475 0 0.7071067811865475 0.7071067811865475 0 0.9659258262890687 0.2588190451025195 0 0.9659258262890687 0.2588190451025195 0 0.8660254037844393 0.4999999999999992 0 0.8660254037844393 0.4999999999999992 0 + + + + + + + + + + + + + + +

0 1 2 1 0 3 2 4 5 4 2 1 6 3 0 3 6 7 8 4 9 4 8 5 10 7 6 7 10 11 12 9 13 9 12 8 14 11 10 11 14 15 16 13 17 13 16 12 18 15 14 15 18 19 20 17 21 17 20 16 18 22 19 22 18 23 24 21 25 21 24 20 23 26 22 26 23 27 28 25 29 25 28 24 27 30 26 30 27 31 32 28 29 28 32 33 31 34 30 34 31 35 36 33 32 33 36 37 35 38 34 38 35 39 40 37 36 37 40 41 39 42 38 42 39 43 44 41 40 41 44 45 42 46 47 46 42 43 47 45 44 45 47 46

+
+
+
+ + + + 49.88188976377955 7.182685229005588 0.604869657207319 49.88188976377955 0.7153153851313138 1.166727690057971 49.88188976377955 0.7153153851313135 0.604869657207319 49.88188976377955 7.182685229005587 1.166727690057971 51.18110236220473 0.7153153851313135 0.604869657207319 49.88188976377955 7.182685229005588 0.604869657207319 49.88188976377955 0.7153153851313135 0.604869657207319 51.18110236220473 7.182685229005588 0.604869657207319 51.18110236220473 7.182685229005587 1.166727690057971 49.88188976377955 7.182685229005588 0.604869657207319 51.18110236220473 7.182685229005588 0.604869657207319 49.88188976377955 7.182685229005587 1.166727690057971 51.18110236220473 7.182685229005587 1.166727690057971 49.88188976377955 0.7153153851313138 1.166727690057971 49.88188976377955 7.182685229005587 1.166727690057971 51.18110236220473 0.7153153851313138 1.166727690057971 49.88188976377955 0.7153153851313138 1.166727690057971 51.18110236220473 0.7153153851313135 0.604869657207319 49.88188976377955 0.7153153851313135 0.604869657207319 51.18110236220473 0.7153153851313138 1.166727690057971 + + + + + + + + + + 1 0 0 1 0 0 1 0 0 1 0 0 -0 -0 1 -0 -0 1 -0 -0 1 -0 -0 1 -0 -1 -1.580787970928972e-015 -0 -1 -1.580787970928972e-015 -0 -1 -1.580787970928972e-015 -0 -1 -1.580787970928972e-015 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 -0 -1 -0 1 -3.95196992732243e-016 -0 1 -3.95196992732243e-016 -0 1 -3.95196992732243e-016 -0 1 -3.95196992732243e-016 + + + + + + + + + + + + + + +

0 1 2 1 0 3 4 5 6 5 4 7 8 9 10 9 8 11 12 13 14 13 12 15 16 17 18 17 16 19

+
+
+
+ + + + 43.3770845465892 7.368501434310447 8.326672684688674e-016 43.37882183390003 7.395007316609055 8.326672684688674e-016 + + + + + + + + + + + + + +

1 0

+
+
+
+ + + + 43.55364811608248 7.569833598791506 8.326672684688674e-016 43.58015399838109 7.571570886102331 8.326672684688674e-016 + + + + + + + + + + + + + +

1 0

+
+
+
+ + + + 51.06260368681876 0.1184986753859656 0 0 0 0 51.06260368681876 0.1184986753859656 2.165354330708662 + + + + + + + + + + + + + +

1 0 0 2

+
+
+
+ + + + 0 0 2.834645669291339 0 0 2.165354330708662 + + + + + + + + + + + + + +

1 0

+
+
+
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + 0.1254901960784314 0.2117647058823529 0.2274509803921569 1 + + + + + + + + + + + 0.2431372549019608 0.3568627450980392 0.4352941176470588 1 + + + + + + + + + + + 0.6627450980392157 0.6627450980392157 0.6627450980392157 1 + + + + + + + + + + + 0 0 0 1 + + + + + + + + + + + 0.2156862745098039 0.3568627450980392 0.3843137254901961 1 + + + + + + + + + + + 0.2431372549019608 0.3568627450980392 0.4352941176470588 1 + + + 1 + + + + + + + + + +
diff --git a/ros-realsense-nav/turtlebot/robot_description/r200.launch.xml b/ros-realsense-nav/turtlebot/robot_description/r200.launch.xml new file mode 100644 index 0000000000..1e764e3c03 --- /dev/null +++ b/ros-realsense-nav/turtlebot/robot_description/r200.launch.xml @@ -0,0 +1,35 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ros-realsense-nav/turtlebot/robot_description/turtlebot_library_extended.urdf.xacro b/ros-realsense-nav/turtlebot/robot_description/turtlebot_library_extended.urdf.xacro new file mode 100644 index 0000000000..31c9de673a --- /dev/null +++ b/ros-realsense-nav/turtlebot/robot_description/turtlebot_library_extended.urdf.xacro @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + + + + + diff --git a/ros-realsense-nav/turtlebot/robot_description/urdf/sensors/r200.urdf.xacro b/ros-realsense-nav/turtlebot/robot_description/urdf/sensors/r200.urdf.xacro new file mode 100644 index 0000000000..d18618589b --- /dev/null +++ b/ros-realsense-nav/turtlebot/robot_description/urdf/sensors/r200.urdf.xacro @@ -0,0 +1,96 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ros-realsense-nav/turtlebot/robot_description/urdf/stacks/minimal.urdf.xacro b/ros-realsense-nav/turtlebot/robot_description/urdf/stacks/minimal.urdf.xacro new file mode 100644 index 0000000000..17ff013e77 --- /dev/null +++ b/ros-realsense-nav/turtlebot/robot_description/urdf/stacks/minimal.urdf.xacro @@ -0,0 +1,84 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/ros-realsense-nav/turtlebot/rviz/navigation_r200.rviz b/ros-realsense-nav/turtlebot/rviz/navigation_r200.rviz new file mode 100644 index 0000000000..e3a33f2bf2 --- /dev/null +++ b/ros-realsense-nav/turtlebot/rviz/navigation_r200.rviz @@ -0,0 +1,379 @@ +Panels: + - Class: rviz/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: + - /TF1/Frames1 + - /TF1/Tree1 + - /Global Map1/Planner1 + - /Local Map1 + - /Image1 + Splitter Ratio: 0.5 + Tree Height: 409 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.588679 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: Image +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.03 + 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 + - Class: rviz/TF + Enabled: false + Frame Timeout: 15 + Frames: + All Enabled: false + Marker Scale: 1 + Name: TF + Show Arrows: true + Show Axes: true + Show Names: false + Tree: + {} + Update Interval: 0 + Value: false + - 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; 255; 255 + Color Transformer: Intensity + 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.01 + Style: Squares + Topic: /scan + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 255; 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: Bumper Hit + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.08 + Style: Spheres + Topic: /mobile_base/sensors/bumper_pointcloud + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 0.7 + Class: rviz/Map + Color Scheme: map + Draw Behind: false + Enabled: true + Name: Map + Topic: /map + Value: true + - Class: rviz/Group + Displays: + - Alpha: 0.7 + Class: rviz/Map + Color Scheme: costmap + Draw Behind: true + Enabled: true + Name: Costmap + Topic: /move_base/global_costmap/costmap + Value: true + - Alpha: 1 + Buffer Length: 1 + Class: rviz/Path + Color: 255; 0; 0 + Enabled: true + Line Style: Lines + Line Width: 0.03 + Name: Planner + Offset: + X: 0 + Y: 0 + Z: 0 + Topic: /move_base/DWAPlannerROS/global_plan + Value: true + Enabled: true + Name: Global Map + - Class: rviz/Group + Displays: + - Alpha: 0.7 + Class: rviz/Map + Color Scheme: costmap + Draw Behind: false + Enabled: true + Name: Costmap + Topic: /move_base/local_costmap/costmap + Value: true + - Alpha: 1 + Buffer Length: 1 + Class: rviz/Path + Color: 0; 12; 255 + Enabled: true + Line Style: Lines + Line Width: 0.03 + Name: Planner + Offset: + X: 0 + Y: 0 + Z: 0 + Topic: /move_base/DWAPlannerROS/local_plan + Value: true + - Alpha: 0.8 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: total_cost + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 785.05 + Min Color: 0; 0; 0 + Min Intensity: 29.39 + Name: Cost Cloud + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.04 + Style: Flat Squares + Topic: /move_base/DWAPlannerROS/cost_cloud + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: total_cost + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 9.621 + Min Color: 0; 0; 0 + Min Intensity: 3.621 + Name: Trajectory Cloud + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.04 + Style: Boxes + Topic: /move_base/DWAPlannerROS/trajectory_cloud + Use Fixed Frame: true + Use rainbow: false + Value: true + Enabled: true + Name: Local Map + - Arrow Length: 0.2 + Class: rviz/PoseArray + Color: 0; 192; 0 + Enabled: true + Name: Amcl Particle Swarm + Topic: /particlecloud + Value: true + - Alpha: 1 + Buffer Length: 1 + Class: rviz/Path + Color: 25; 255; 0 + Enabled: true + Line Style: Lines + Line Width: 0.03 + Name: Full Plan + Offset: + X: 0 + Y: 0 + Z: 0 + Topic: /move_base/NavfnROS/plan + Value: true + - Class: rviz/Image + Enabled: true + Image Topic: /camera/depth/image_raw + Max Value: 2500 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: false + Queue Size: 2 + Transport Hint: raw + Value: true + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: map + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/MoveCamera + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/Select + - Class: rviz/SetInitialPose + Topic: /initialpose + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/Measure + - Class: rviz/PublishPoint + Single click: true + Topic: /clicked_point + Value: true + Views: + Current: + Angle: 0 + Class: rviz/TopDownOrtho + Enable Stereo Rendering: + Stereo Eye Separation: 0.06 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Name: Current View + Near Clip Distance: 0.01 + Scale: 80 + Target Frame: + Value: TopDownOrtho (rviz) + X: 0 + Y: 0 + Saved: + - Class: rviz/Orbit + Distance: 13 + Enable Stereo Rendering: + Stereo Eye Separation: 0.06 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: 0 + Y: 0 + Z: 0 + Name: Mapping3 + Near Clip Distance: 0.01 + Pitch: 1.5648 + Target Frame: + Value: Orbit (rviz) + Yaw: 3.13659 + - Angle: 0 + Class: rviz/TopDownOrtho + Enable Stereo Rendering: + Stereo Eye Separation: 0.06 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Name: Mapping + Near Clip Distance: 0.01 + Scale: 80 + Target Frame: + Value: TopDownOrtho (rviz) + X: 0 + Y: 0 +Window Geometry: + Displays: + collapsed: false + Height: 985 + Hide Left Dock: false + Hide Right Dock: false + Image: + collapsed: false + QMainWindow State: 000000ff00000000fd00000004000000000000018000000393fc0200000006fb0000001200530065006c0065006300740069006f006e00000000280000009b0000006400fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000002800000228000000dd00fffffffb0000000a0049006d0061006700650100000256000001650000001600ffffff000000010000010f00000393fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000002800000393000000b000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000073f0000003efc0100000002fb0000000800540069006d006500000000000000073f000002f600fffffffb0000000800540069006d00650100000000000004500000000000000000000004a40000039300000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1855 + X: 63 + Y: 22 diff --git a/ros-realsense-nav/turtlebot/rviz/navigation_r200_without_depth.rviz b/ros-realsense-nav/turtlebot/rviz/navigation_r200_without_depth.rviz new file mode 100644 index 0000000000..8d45ceee6d --- /dev/null +++ b/ros-realsense-nav/turtlebot/rviz/navigation_r200_without_depth.rviz @@ -0,0 +1,540 @@ +Panels: + - Class: rviz/Displays + Help Height: 78 + Name: Displays + Property Tree Widget: + Expanded: + - /TF1/Frames1 + - /TF1/Tree1 + - /Global Map1/Planner1 + - /Local Map1 + - /Image1 + Splitter Ratio: 0.5 + Tree Height: 772 + - Class: rviz/Selection + Name: Selection + - Class: rviz/Tool Properties + Expanded: + - /2D Pose Estimate1 + - /2D Nav Goal1 + - /Publish Point1 + Name: Tool Properties + Splitter Ratio: 0.588679 + - Class: rviz/Views + Expanded: + - /Current View1 + Name: Views + Splitter Ratio: 0.5 + - Class: rviz/Time + Experimental: false + Name: Time + SyncMode: 0 + SyncSource: Image +Visualization Manager: + Class: "" + Displays: + - Alpha: 0.5 + Cell Size: 1 + Class: rviz/Grid + Color: 160; 160; 164 + Enabled: true + Line Style: + Line Width: 0.03 + 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 + base_footprint: + Alpha: 1 + Show Axes: false + Show Trail: false + base_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + camera_depth_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + camera_depth_optical_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + camera_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + camera_rgb_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + camera_rgb_optical_frame: + Alpha: 1 + Show Axes: false + Show Trail: false + caster_back_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + caster_front_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + cliff_sensor_front_link: + Alpha: 1 + Show Axes: false + Show Trail: false + cliff_sensor_left_link: + Alpha: 1 + Show Axes: false + Show Trail: false + cliff_sensor_right_link: + Alpha: 1 + Show Axes: false + Show Trail: false + gyro_link: + Alpha: 1 + Show Axes: false + Show Trail: false + plate_bottom_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + plate_middle_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + plate_top_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + pole_bottom_0_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + pole_bottom_1_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + pole_bottom_2_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + pole_bottom_3_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + pole_bottom_4_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + pole_bottom_5_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + pole_kinect_0_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + pole_kinect_1_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + pole_middle_0_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + pole_middle_1_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + pole_middle_2_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + pole_middle_3_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + pole_top_0_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + pole_top_1_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + pole_top_2_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + pole_top_3_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + wheel_left_link: + Alpha: 1 + Show Axes: false + Show Trail: false + Value: true + wheel_right_link: + 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 + - Class: rviz/TF + Enabled: false + Frame Timeout: 15 + Frames: + All Enabled: false + Marker Scale: 1 + Name: TF + Show Arrows: true + Show Axes: true + Show Names: false + Tree: + {} + Update Interval: 0 + Value: false + - 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; 255; 255 + Color Transformer: Intensity + 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.01 + Style: Squares + Topic: /scan + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: intensity + Class: rviz/PointCloud2 + Color: 255; 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: Bumper Hit + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.08 + Style: Spheres + Topic: /mobile_base/sensors/bumper_pointcloud + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 0.7 + Class: rviz/Map + Color Scheme: map + Draw Behind: false + Enabled: true + Name: Map + Topic: /map + Value: true + - Class: rviz/Group + Displays: + - Alpha: 0.7 + Class: rviz/Map + Color Scheme: costmap + Draw Behind: true + Enabled: true + Name: Costmap + Topic: /move_base/global_costmap/costmap + Value: true + - Alpha: 1 + Buffer Length: 1 + Class: rviz/Path + Color: 255; 0; 0 + Enabled: true + Line Style: Lines + Line Width: 0.03 + Name: Planner + Offset: + X: 0 + Y: 0 + Z: 0 + Topic: /move_base/DWAPlannerROS/global_plan + Value: true + Enabled: true + Name: Global Map + - Class: rviz/Group + Displays: + - Alpha: 0.7 + Class: rviz/Map + Color Scheme: costmap + Draw Behind: false + Enabled: true + Name: Costmap + Topic: /move_base/local_costmap/costmap + Value: true + - Alpha: 1 + Buffer Length: 1 + Class: rviz/Path + Color: 0; 12; 255 + Enabled: true + Line Style: Lines + Line Width: 0.03 + Name: Planner + Offset: + X: 0 + Y: 0 + Z: 0 + Topic: /move_base/DWAPlannerROS/local_plan + Value: true + - Alpha: 0.8 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: total_cost + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 785.05 + Min Color: 0; 0; 0 + Min Intensity: 29.39 + Name: Cost Cloud + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.04 + Style: Flat Squares + Topic: /move_base/DWAPlannerROS/cost_cloud + Use Fixed Frame: true + Use rainbow: true + Value: true + - Alpha: 1 + Autocompute Intensity Bounds: true + Autocompute Value Bounds: + Max Value: 10 + Min Value: -10 + Value: true + Axis: Z + Channel Name: total_cost + Class: rviz/PointCloud2 + Color: 255; 255; 255 + Color Transformer: Intensity + Decay Time: 0 + Enabled: true + Invert Rainbow: false + Max Color: 255; 255; 255 + Max Intensity: 9.621 + Min Color: 0; 0; 0 + Min Intensity: 3.621 + Name: Trajectory Cloud + Position Transformer: XYZ + Queue Size: 10 + Selectable: true + Size (Pixels): 3 + Size (m): 0.04 + Style: Boxes + Topic: /move_base/DWAPlannerROS/trajectory_cloud + Use Fixed Frame: true + Use rainbow: false + Value: true + Enabled: true + Name: Local Map + - Arrow Length: 0.2 + Class: rviz/PoseArray + Color: 0; 192; 0 + Enabled: true + Name: Amcl Particle Swarm + Topic: /particlecloud + Value: true + - Alpha: 1 + Buffer Length: 1 + Class: rviz/Path + Color: 25; 255; 0 + Enabled: true + Line Style: Lines + Line Width: 0.03 + Name: Full Plan + Offset: + X: 0 + Y: 0 + Z: 0 + Topic: /move_base/NavfnROS/plan + Value: true + - Class: rviz/Image + Enabled: false + Image Topic: /camera/depth/image_raw + Max Value: 2500 + Median window: 5 + Min Value: 0 + Name: Image + Normalize Range: false + Queue Size: 2 + Transport Hint: raw + Value: false + Enabled: true + Global Options: + Background Color: 48; 48; 48 + Fixed Frame: map + Frame Rate: 30 + Name: root + Tools: + - Class: rviz/MoveCamera + - Class: rviz/Interact + Hide Inactive Objects: true + - Class: rviz/Select + - Class: rviz/SetInitialPose + Topic: /initialpose + - Class: rviz/SetGoal + Topic: /move_base_simple/goal + - Class: rviz/Measure + - Class: rviz/PublishPoint + Single click: true + Topic: /clicked_point + Value: true + Views: + Current: + Angle: 0 + Class: rviz/TopDownOrtho + Enable Stereo Rendering: + Stereo Eye Separation: 0.06 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Name: Current View + Near Clip Distance: 0.01 + Scale: 80 + Target Frame: + Value: TopDownOrtho (rviz) + X: 0 + Y: 0 + Saved: + - Class: rviz/Orbit + Distance: 13 + Enable Stereo Rendering: + Stereo Eye Separation: 0.06 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Focal Point: + X: 0 + Y: 0 + Z: 0 + Name: Mapping3 + Near Clip Distance: 0.01 + Pitch: 1.5648 + Target Frame: + Value: Orbit (rviz) + Yaw: 3.13659 + - Angle: 0 + Class: rviz/TopDownOrtho + Enable Stereo Rendering: + Stereo Eye Separation: 0.06 + Stereo Focal Distance: 1 + Swap Stereo Eyes: false + Value: false + Name: Mapping + Near Clip Distance: 0.01 + Scale: 80 + Target Frame: + Value: TopDownOrtho (rviz) + X: 0 + Y: 0 +Window Geometry: + Displays: + collapsed: false + Height: 985 + Hide Left Dock: false + Hide Right Dock: false + Image: + collapsed: false + QMainWindow State: 000000ff00000000fd00000004000000000000018000000393fc0200000006fb0000001200530065006c0065006300740069006f006e00000000280000009b0000006400fffffffb0000001e0054006f006f006c002000500072006f007000650072007400690065007302000001ed000001df00000185000000a3fb000000120056006900650077007300200054006f006f02000001df000002110000018500000122fb000000200054006f006f006c002000500072006f0070006500720074006900650073003203000002880000011d000002210000017afb000000100044006900730070006c006100790073010000002800000393000000dd00fffffffb0000000a0049006d0061006700650000000256000001650000001600ffffff000000010000010f00000393fc0200000003fb0000001e0054006f006f006c002000500072006f00700065007200740069006500730100000041000000780000000000000000fb0000000a00560069006500770073010000002800000393000000b000fffffffb0000001200530065006c0065006300740069006f006e010000025a000000b200000000000000000000000200000490000000a9fc0100000001fb0000000a00560069006500770073030000004e00000080000002e100000197000000030000073f0000003efc0100000002fb0000000800540069006d006500000000000000073f000002f600fffffffb0000000800540069006d00650100000000000004500000000000000000000004a40000039300000004000000040000000800000008fc0000000100000002000000010000000a0054006f006f006c00730100000000ffffffff0000000000000000 + Selection: + collapsed: false + Time: + collapsed: false + Tool Properties: + collapsed: false + Views: + collapsed: false + Width: 1855 + X: 63 + Y: 14 From a9ff98a4b35e9aec20e9fe743b5d9323a648158e Mon Sep 17 00:00:00 2001 From: Kevin Wells Date: Tue, 23 Feb 2016 18:42:56 -0800 Subject: [PATCH 029/124] Move navigation files and documentation into appropriate location. The navigation files were in the wrong spot and would not allow for a proper catkin_make. The files have been moved into the correct spot and the entire navigation process has been tested. --- .../ros-realsense-nav}/turtlebot/README.md | 0 .../turtlebot/doc/img/bag_screen.png | Bin .../turtlebot/doc/img/mapping_screen.png | Bin .../turtlebot/doc/img/screen-ds4-nav.png | Bin .../ros-realsense-nav}/turtlebot/doc/style-doc.css | 0 .../turtlebot/install_realsense_navigation.sh | 2 +- .../ros-realsense-nav}/turtlebot/launch/amcl.launch | 0 .../turtlebot/launch/gmapping.launch | 0 .../turtlebot/launch/navigation_demo.launch | 0 .../launch/realsense_robot_description.launch | 0 .../turtlebot/launch/simulate_mapping.launch | 0 .../ros-realsense-nav}/turtlebot/package.xml | 0 .../robot_description/custom_costmap_params.yaml | 0 .../kobuki_minimal_r200.urdf.xacro | 0 .../robot_description/meshes/sensors/r200.dae | 0 .../meshes/sensors/r200_entire.dae | 0 .../meshes/sensors/r200_entire/texture0.jpg | Bin .../robot_description/meshes/sensors/r200_only.dae | 0 .../turtlebot/robot_description/r200.launch.xml | 0 .../turtlebot_library_extended.urdf.xacro | 0 .../robot_description/urdf/sensors/r200.urdf.xacro | 0 .../urdf/stacks/minimal.urdf.xacro | 0 .../turtlebot/rviz/navigation_r200.rviz | 0 .../rviz/navigation_r200_without_depth.rviz | 0 24 files changed, 1 insertion(+), 1 deletion(-) rename {ros-realsense-nav => camera/ros-realsense-nav}/turtlebot/README.md (100%) rename {ros-realsense-nav => camera/ros-realsense-nav}/turtlebot/doc/img/bag_screen.png (100%) rename {ros-realsense-nav => camera/ros-realsense-nav}/turtlebot/doc/img/mapping_screen.png (100%) rename {ros-realsense-nav => camera/ros-realsense-nav}/turtlebot/doc/img/screen-ds4-nav.png (100%) rename {ros-realsense-nav => camera/ros-realsense-nav}/turtlebot/doc/style-doc.css (100%) rename {ros-realsense-nav => camera/ros-realsense-nav}/turtlebot/install_realsense_navigation.sh (86%) mode change 100644 => 100755 rename {ros-realsense-nav => camera/ros-realsense-nav}/turtlebot/launch/amcl.launch (100%) rename {ros-realsense-nav => camera/ros-realsense-nav}/turtlebot/launch/gmapping.launch (100%) rename {ros-realsense-nav => camera/ros-realsense-nav}/turtlebot/launch/navigation_demo.launch (100%) rename {ros-realsense-nav => camera/ros-realsense-nav}/turtlebot/launch/realsense_robot_description.launch (100%) rename {ros-realsense-nav => camera/ros-realsense-nav}/turtlebot/launch/simulate_mapping.launch (100%) rename {ros-realsense-nav => camera/ros-realsense-nav}/turtlebot/package.xml (100%) rename {ros-realsense-nav => camera/ros-realsense-nav}/turtlebot/robot_description/custom_costmap_params.yaml (100%) rename {ros-realsense-nav => camera/ros-realsense-nav}/turtlebot/robot_description/kobuki_minimal_r200.urdf.xacro (100%) rename {ros-realsense-nav => camera/ros-realsense-nav}/turtlebot/robot_description/meshes/sensors/r200.dae (100%) rename {ros-realsense-nav => camera/ros-realsense-nav}/turtlebot/robot_description/meshes/sensors/r200_entire.dae (100%) rename {ros-realsense-nav => camera/ros-realsense-nav}/turtlebot/robot_description/meshes/sensors/r200_entire/texture0.jpg (100%) rename {ros-realsense-nav => camera/ros-realsense-nav}/turtlebot/robot_description/meshes/sensors/r200_only.dae (100%) rename {ros-realsense-nav => camera/ros-realsense-nav}/turtlebot/robot_description/r200.launch.xml (100%) rename {ros-realsense-nav => camera/ros-realsense-nav}/turtlebot/robot_description/turtlebot_library_extended.urdf.xacro (100%) rename {ros-realsense-nav => camera/ros-realsense-nav}/turtlebot/robot_description/urdf/sensors/r200.urdf.xacro (100%) rename {ros-realsense-nav => camera/ros-realsense-nav}/turtlebot/robot_description/urdf/stacks/minimal.urdf.xacro (100%) rename {ros-realsense-nav => camera/ros-realsense-nav}/turtlebot/rviz/navigation_r200.rviz (100%) rename {ros-realsense-nav => camera/ros-realsense-nav}/turtlebot/rviz/navigation_r200_without_depth.rviz (100%) diff --git a/ros-realsense-nav/turtlebot/README.md b/camera/ros-realsense-nav/turtlebot/README.md similarity index 100% rename from ros-realsense-nav/turtlebot/README.md rename to camera/ros-realsense-nav/turtlebot/README.md diff --git a/ros-realsense-nav/turtlebot/doc/img/bag_screen.png b/camera/ros-realsense-nav/turtlebot/doc/img/bag_screen.png similarity index 100% rename from ros-realsense-nav/turtlebot/doc/img/bag_screen.png rename to camera/ros-realsense-nav/turtlebot/doc/img/bag_screen.png diff --git a/ros-realsense-nav/turtlebot/doc/img/mapping_screen.png b/camera/ros-realsense-nav/turtlebot/doc/img/mapping_screen.png similarity index 100% rename from ros-realsense-nav/turtlebot/doc/img/mapping_screen.png rename to camera/ros-realsense-nav/turtlebot/doc/img/mapping_screen.png diff --git a/ros-realsense-nav/turtlebot/doc/img/screen-ds4-nav.png b/camera/ros-realsense-nav/turtlebot/doc/img/screen-ds4-nav.png similarity index 100% rename from ros-realsense-nav/turtlebot/doc/img/screen-ds4-nav.png rename to camera/ros-realsense-nav/turtlebot/doc/img/screen-ds4-nav.png diff --git a/ros-realsense-nav/turtlebot/doc/style-doc.css b/camera/ros-realsense-nav/turtlebot/doc/style-doc.css similarity index 100% rename from ros-realsense-nav/turtlebot/doc/style-doc.css rename to camera/ros-realsense-nav/turtlebot/doc/style-doc.css diff --git a/ros-realsense-nav/turtlebot/install_realsense_navigation.sh b/camera/ros-realsense-nav/turtlebot/install_realsense_navigation.sh old mode 100644 new mode 100755 similarity index 86% rename from ros-realsense-nav/turtlebot/install_realsense_navigation.sh rename to camera/ros-realsense-nav/turtlebot/install_realsense_navigation.sh index 455cebe267..c6707d6b42 --- a/ros-realsense-nav/turtlebot/install_realsense_navigation.sh +++ b/camera/ros-realsense-nav/turtlebot/install_realsense_navigation.sh @@ -6,5 +6,5 @@ sudo cp ./robot_description/kobuki_minimal_r200.urdf.xacro /opt/ros/$ROS_DISTRO/share/turtlebot_description/robots/ sudo cp ./robot_description/r200.launch.xml /opt/ros/$ROS_DISTRO/share/turtlebot_bringup/launch/includes/3dsensor/ -sudo mkdir /opt/ros/$ROS_DISTRO/share/realsense_navigation +sudo mkdir -p /opt/ros/$ROS_DISTRO/share/realsense_navigation sudo cp -r ./* /opt/ros/$ROS_DISTRO/share/realsense_navigation diff --git a/ros-realsense-nav/turtlebot/launch/amcl.launch b/camera/ros-realsense-nav/turtlebot/launch/amcl.launch similarity index 100% rename from ros-realsense-nav/turtlebot/launch/amcl.launch rename to camera/ros-realsense-nav/turtlebot/launch/amcl.launch diff --git a/ros-realsense-nav/turtlebot/launch/gmapping.launch b/camera/ros-realsense-nav/turtlebot/launch/gmapping.launch similarity index 100% rename from ros-realsense-nav/turtlebot/launch/gmapping.launch rename to camera/ros-realsense-nav/turtlebot/launch/gmapping.launch diff --git a/ros-realsense-nav/turtlebot/launch/navigation_demo.launch b/camera/ros-realsense-nav/turtlebot/launch/navigation_demo.launch similarity index 100% rename from ros-realsense-nav/turtlebot/launch/navigation_demo.launch rename to camera/ros-realsense-nav/turtlebot/launch/navigation_demo.launch diff --git a/ros-realsense-nav/turtlebot/launch/realsense_robot_description.launch b/camera/ros-realsense-nav/turtlebot/launch/realsense_robot_description.launch similarity index 100% rename from ros-realsense-nav/turtlebot/launch/realsense_robot_description.launch rename to camera/ros-realsense-nav/turtlebot/launch/realsense_robot_description.launch diff --git a/ros-realsense-nav/turtlebot/launch/simulate_mapping.launch b/camera/ros-realsense-nav/turtlebot/launch/simulate_mapping.launch similarity index 100% rename from ros-realsense-nav/turtlebot/launch/simulate_mapping.launch rename to camera/ros-realsense-nav/turtlebot/launch/simulate_mapping.launch diff --git a/ros-realsense-nav/turtlebot/package.xml b/camera/ros-realsense-nav/turtlebot/package.xml similarity index 100% rename from ros-realsense-nav/turtlebot/package.xml rename to camera/ros-realsense-nav/turtlebot/package.xml diff --git a/ros-realsense-nav/turtlebot/robot_description/custom_costmap_params.yaml b/camera/ros-realsense-nav/turtlebot/robot_description/custom_costmap_params.yaml similarity index 100% rename from ros-realsense-nav/turtlebot/robot_description/custom_costmap_params.yaml rename to camera/ros-realsense-nav/turtlebot/robot_description/custom_costmap_params.yaml diff --git a/ros-realsense-nav/turtlebot/robot_description/kobuki_minimal_r200.urdf.xacro b/camera/ros-realsense-nav/turtlebot/robot_description/kobuki_minimal_r200.urdf.xacro similarity index 100% rename from ros-realsense-nav/turtlebot/robot_description/kobuki_minimal_r200.urdf.xacro rename to camera/ros-realsense-nav/turtlebot/robot_description/kobuki_minimal_r200.urdf.xacro diff --git a/ros-realsense-nav/turtlebot/robot_description/meshes/sensors/r200.dae b/camera/ros-realsense-nav/turtlebot/robot_description/meshes/sensors/r200.dae similarity index 100% rename from ros-realsense-nav/turtlebot/robot_description/meshes/sensors/r200.dae rename to camera/ros-realsense-nav/turtlebot/robot_description/meshes/sensors/r200.dae diff --git a/ros-realsense-nav/turtlebot/robot_description/meshes/sensors/r200_entire.dae b/camera/ros-realsense-nav/turtlebot/robot_description/meshes/sensors/r200_entire.dae similarity index 100% rename from ros-realsense-nav/turtlebot/robot_description/meshes/sensors/r200_entire.dae rename to camera/ros-realsense-nav/turtlebot/robot_description/meshes/sensors/r200_entire.dae diff --git a/ros-realsense-nav/turtlebot/robot_description/meshes/sensors/r200_entire/texture0.jpg b/camera/ros-realsense-nav/turtlebot/robot_description/meshes/sensors/r200_entire/texture0.jpg similarity index 100% rename from ros-realsense-nav/turtlebot/robot_description/meshes/sensors/r200_entire/texture0.jpg rename to camera/ros-realsense-nav/turtlebot/robot_description/meshes/sensors/r200_entire/texture0.jpg diff --git a/ros-realsense-nav/turtlebot/robot_description/meshes/sensors/r200_only.dae b/camera/ros-realsense-nav/turtlebot/robot_description/meshes/sensors/r200_only.dae similarity index 100% rename from ros-realsense-nav/turtlebot/robot_description/meshes/sensors/r200_only.dae rename to camera/ros-realsense-nav/turtlebot/robot_description/meshes/sensors/r200_only.dae diff --git a/ros-realsense-nav/turtlebot/robot_description/r200.launch.xml b/camera/ros-realsense-nav/turtlebot/robot_description/r200.launch.xml similarity index 100% rename from ros-realsense-nav/turtlebot/robot_description/r200.launch.xml rename to camera/ros-realsense-nav/turtlebot/robot_description/r200.launch.xml diff --git a/ros-realsense-nav/turtlebot/robot_description/turtlebot_library_extended.urdf.xacro b/camera/ros-realsense-nav/turtlebot/robot_description/turtlebot_library_extended.urdf.xacro similarity index 100% rename from ros-realsense-nav/turtlebot/robot_description/turtlebot_library_extended.urdf.xacro rename to camera/ros-realsense-nav/turtlebot/robot_description/turtlebot_library_extended.urdf.xacro diff --git a/ros-realsense-nav/turtlebot/robot_description/urdf/sensors/r200.urdf.xacro b/camera/ros-realsense-nav/turtlebot/robot_description/urdf/sensors/r200.urdf.xacro similarity index 100% rename from ros-realsense-nav/turtlebot/robot_description/urdf/sensors/r200.urdf.xacro rename to camera/ros-realsense-nav/turtlebot/robot_description/urdf/sensors/r200.urdf.xacro diff --git a/ros-realsense-nav/turtlebot/robot_description/urdf/stacks/minimal.urdf.xacro b/camera/ros-realsense-nav/turtlebot/robot_description/urdf/stacks/minimal.urdf.xacro similarity index 100% rename from ros-realsense-nav/turtlebot/robot_description/urdf/stacks/minimal.urdf.xacro rename to camera/ros-realsense-nav/turtlebot/robot_description/urdf/stacks/minimal.urdf.xacro diff --git a/ros-realsense-nav/turtlebot/rviz/navigation_r200.rviz b/camera/ros-realsense-nav/turtlebot/rviz/navigation_r200.rviz similarity index 100% rename from ros-realsense-nav/turtlebot/rviz/navigation_r200.rviz rename to camera/ros-realsense-nav/turtlebot/rviz/navigation_r200.rviz diff --git a/ros-realsense-nav/turtlebot/rviz/navigation_r200_without_depth.rviz b/camera/ros-realsense-nav/turtlebot/rviz/navigation_r200_without_depth.rviz similarity index 100% rename from ros-realsense-nav/turtlebot/rviz/navigation_r200_without_depth.rviz rename to camera/ros-realsense-nav/turtlebot/rviz/navigation_r200_without_depth.rviz From b57ffe41d8a95c503653ba251fb8901d52f3a03f Mon Sep 17 00:00:00 2001 From: kevincwells Date: Wed, 24 Feb 2016 16:52:01 -0800 Subject: [PATCH 030/124] Add license headers to new .cpp and .h files. Added the appropriate BSD 3-clause license header to the tops of the new .cpp and .h files brought in from Master. --- camera/test/realsense_camera_test_node.cpp | 32 ++++++++++++++++--- camera/test/realsense_camera_test_node.h | 32 ++++++++++++++++--- .../test/realsense_camera_test_rgbd_node.cpp | 30 +++++++++++++++++ camera/test/realsense_camera_test_rgbd_node.h | 30 +++++++++++++++++ 4 files changed, 114 insertions(+), 10 deletions(-) diff --git a/camera/test/realsense_camera_test_node.cpp b/camera/test/realsense_camera_test_node.cpp index 4b1387760a..6379c9ead7 100644 --- a/camera/test/realsense_camera_test_node.cpp +++ b/camera/test/realsense_camera_test_node.cpp @@ -1,9 +1,31 @@ /****************************************************************************** - INTEL CORPORATION PROPRIETARY INFORMATION - This software is supplied under the terms of a license agreement or nondisclosure - agreement with Intel Corporation and may not be copied or disclosed except in - accordance with the terms of that agreement - Copyright(c) 2011-2016 Intel Corporation. All Rights Reserved. + Copyright (c) 2016, Intel Corporation + All rights reserved. + + Redistribution and use in source and binary forms, with or without + modification, are permitted provided that the following conditions are met: + + 1. Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + + 2. Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + + 3. Neither the name of the copyright holder nor the names of its contributors + may be used to endorse or promote products derived from this software without + specific prior written permission. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *******************************************************************************/ #include "gtest/gtest.h" diff --git a/camera/test/realsense_camera_test_node.h b/camera/test/realsense_camera_test_node.h index 8679479b43..7233b020ec 100644 --- a/camera/test/realsense_camera_test_node.h +++ b/camera/test/realsense_camera_test_node.h @@ -1,9 +1,31 @@ /****************************************************************************** - INTEL CORPORATION PROPRIETARY INFORMATION - This software is supplied under the terms of a license agreement or nondisclosure - agreement with Intel Corporation and may not be copied or disclosed except in - accordance with the terms of that agreement - Copyright(c) 2011-2016 Intel Corporation. All Rights Reserved. + Copyright (c) 2016, Intel Corporation + All rights reserved. + + Redistribution and use in source and binary forms, with or without + modification, are permitted provided that the following conditions are met: + + 1. Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + + 2. Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + + 3. Neither the name of the copyright holder nor the names of its contributors + may be used to endorse or promote products derived from this software without + specific prior written permission. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *******************************************************************************/ #include diff --git a/camera/test/realsense_camera_test_rgbd_node.cpp b/camera/test/realsense_camera_test_rgbd_node.cpp index 20e7dfafd2..d3cf52ecca 100644 --- a/camera/test/realsense_camera_test_rgbd_node.cpp +++ b/camera/test/realsense_camera_test_rgbd_node.cpp @@ -1,3 +1,33 @@ +/****************************************************************************** + Copyright (c) 2016, Intel Corporation + All rights reserved. + + Redistribution and use in source and binary forms, with or without + modification, are permitted provided that the following conditions are met: + + 1. Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + + 2. Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + + 3. Neither the name of the copyright holder nor the names of its contributors + may be used to endorse or promote products derived from this software without + specific prior written permission. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + *******************************************************************************/ + #include "realsense_camera_test_rgbd_node.h" using namespace std; diff --git a/camera/test/realsense_camera_test_rgbd_node.h b/camera/test/realsense_camera_test_rgbd_node.h index 78a44b3ea0..1f4713e491 100644 --- a/camera/test/realsense_camera_test_rgbd_node.h +++ b/camera/test/realsense_camera_test_rgbd_node.h @@ -1,3 +1,33 @@ +/****************************************************************************** + Copyright (c) 2016, Intel Corporation + All rights reserved. + + Redistribution and use in source and binary forms, with or without + modification, are permitted provided that the following conditions are met: + + 1. Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + + 2. Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + + 3. Neither the name of the copyright holder nor the names of its contributors + may be used to endorse or promote products derived from this software without + specific prior written permission. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + *******************************************************************************/ + #include #include #include From 47fa4326cc7c3595f804b515bb2a2680cfe57990 Mon Sep 17 00:00:00 2001 From: rjingar Date: Wed, 24 Feb 2016 21:37:10 -0800 Subject: [PATCH 031/124] Added dynamic reconfiguration for R200 camera options --- camera/CMakeLists.txt | 10 +++++ camera/cfg/camera_params.cfg | 30 ++++++++++++++ camera/package.xml | 2 + camera/src/realsense_camera_nodelet.cpp | 53 +++++++++++++++++++++++++ camera/src/realsense_camera_nodelet.h | 13 ++++++ 5 files changed, 108 insertions(+) create mode 100755 camera/cfg/camera_params.cfg diff --git a/camera/CMakeLists.txt b/camera/CMakeLists.txt index 7c12c647bb..9b72272811 100644 --- a/camera/CMakeLists.txt +++ b/camera/CMakeLists.txt @@ -14,6 +14,7 @@ set(CMAKE_EXE_LINKER_FLAGS "-pie -z noexecstack -z relro -z now") set(CMAKE_SHARED_LINKER_FLAGS "-z noexecstack -z relro -z now") find_package(catkin REQUIRED COMPONENTS + dynamic_reconfigure roscpp nodelet cv_bridge @@ -37,6 +38,13 @@ generate_messages( std_msgs ) +#add dynamic reconfigure api +generate_dynamic_reconfigure_options( + cfg/camera_params.cfg +) + + + include_directories( ${catkin_INCLUDE_DIRS} ) @@ -46,6 +54,7 @@ target_link_libraries(realsense_camera_nodelet ${catkin_LIBRARIES} /usr/local/lib/librealsense.so ) +add_dependencies(realsense_camera_nodelet ${PROJECT_NAME}_gencfg) add_dependencies(realsense_camera_nodelet realsense_camera_generate_messages_cpp) add_executable(realsense_camera_test test/realsense_camera_test_node.cpp) @@ -53,6 +62,7 @@ target_link_libraries(realsense_camera_test ${catkin_LIBRARIES} ${GTEST_LIBRARIES} ) +add_dependencies(realsense_camera_test ${PROJECT_NAME}_gencfg) add_dependencies(realsense_camera_test realsense_camera_generate_messages_cpp) add_executable(realsense_camera_test_rgbd test/realsense_camera_test_rgbd_node.cpp) diff --git a/camera/cfg/camera_params.cfg b/camera/cfg/camera_params.cfg new file mode 100755 index 0000000000..95502ee366 --- /dev/null +++ b/camera/cfg/camera_params.cfg @@ -0,0 +1,30 @@ +#!/usr/bin/env python + +PACKAGE="realsense_camera" + +from dynamic_reconfigure.parameter_generator_catkin import * + +gen = ParameterGenerator() + +gen.add("COLOR_BACKLIGHT_COMPENSATION", int_t, 0, "Backlight Compensation", 1, 0, 4) +gen.add("COLOR_BRIGHTNESS", int_t, 0, "Brightness", 56, 0, 255) +gen.add("COLOR_CONTRAST", int_t, 0, "Contrast", 32, 16, 64) +gen.add("COLOR_GAIN", int_t, 0, "Gain", 32, 0, 256) +gen.add("COLOR_GAMMA", int_t, 0, "Gamma", 220, 100, 280) +gen.add("COLOR_HUE", int_t, 0, "Hue", 0, -2200, 2200) +gen.add("COLOR_SATURATION", int_t, 0, "Saturation", 128, 0, 255) +gen.add("COLOR_SHARPNESS", int_t, 0, "Sharpness", 0, 0, 7) +gen.add("COLOR_WHITE_BALANCE", int_t, 0, "White Balance", 6500, 2000, 8000) +gen.add("COLOR_ENABLE_AUTO_WHITE_BALANCE", int_t, 0, "Enable Auto White Balance", 1, 0, 1) +gen.add("R200_LR_AUTO_EXPOSURE_ENABLED", int_t, 0, "LR Auto Exposure Enabled", 0, 0, 1) +gen.add("R200_LR_GAIN", int_t, 0, "LR Gain", 400, 100, 6399) +gen.add("R200_LR_EXPOSURE", int_t, 0, "LR Exposure", 164, 1, 330) +gen.add("R200_EMITTER_ENABLED", int_t, 0, "Emitter Enabled", 1, 0, 1) +gen.add("R200_DISPARITY_MULTIPLIER", int_t, 0, "Disparity Multiplier", 32, 1, 1000) +gen.add("R200_AUTO_EXPOSURE_TOP_EDGE", int_t, 0, "Auto Exposure Top Edge", 0, 0, 479) +gen.add("R200_AUTO_EXPOSURE_BOTTOM_EDGE", int_t, 0, "Auto Exposure Bottom Edge", 479, 0, 479) +gen.add("R200_AUTO_EXPOSURE_LEFT_EDGE", int_t, 0, "Auto Exposure Left Edge", 0, 0, 639) +gen.add("R200_AUTO_EXPOSURE_RIGHT_EDGE", int_t, 0, "Auto Exposure Right Edge", 639, 0, 639) + +exit(gen.generate(PACKAGE, "realsense_camera", "camera_params")) + diff --git a/camera/package.xml b/camera/package.xml index 904e0cfdd1..f9fe576836 100644 --- a/camera/package.xml +++ b/camera/package.xml @@ -26,6 +26,7 @@ sensor_msgs rostest pcl_ros + dynamic_reconfigure roscpp nodelet @@ -38,6 +39,7 @@ sensor_msgs rostest pcl_ros + dynamic_reconfigure diff --git a/camera/src/realsense_camera_nodelet.cpp b/camera/src/realsense_camera_nodelet.cpp index b38939c03a..f045af4a7b 100644 --- a/camera/src/realsense_camera_nodelet.cpp +++ b/camera/src/realsense_camera_nodelet.cpp @@ -121,6 +121,9 @@ namespace realsense_camera get_options_service_ = nh.advertiseService (SETTINGS_SERVICE, &RealsenseNodelet::getCameraSettings, this); + mReconfigureServer.reset(new dynamic_reconfigure::Server(getPrivateNodeHandle())); + mReconfigureServer->setCallback(boost::bind(&RealsenseNodelet::configCallback, this, _1, _2)); + bool connected = false; connected = connectToCamera (); @@ -142,6 +145,56 @@ namespace realsense_camera /* *Private Methods. */ + void RealsenseNodelet::configCallback(realsense_camera::camera_paramsConfig &config, uint32_t level) + { + rs_set_device_option(rs_device_, RS_OPTION_COLOR_BACKLIGHT_COMPENSATION, config.COLOR_BACKLIGHT_COMPENSATION, 0); + rs_set_device_option(rs_device_, RS_OPTION_COLOR_BRIGHTNESS, config.COLOR_BRIGHTNESS, 0); + rs_set_device_option(rs_device_, RS_OPTION_COLOR_CONTRAST, config.COLOR_CONTRAST, 0); + rs_set_device_option(rs_device_, RS_OPTION_COLOR_GAIN, config.COLOR_GAIN, 0); + rs_set_device_option(rs_device_, RS_OPTION_COLOR_GAMMA, config.COLOR_GAMMA, 0); + rs_set_device_option(rs_device_, RS_OPTION_COLOR_HUE, config.COLOR_HUE, 0); + rs_set_device_option(rs_device_, RS_OPTION_COLOR_SATURATION, config.COLOR_SATURATION, 0); + rs_set_device_option(rs_device_, RS_OPTION_COLOR_SHARPNESS, config.COLOR_SHARPNESS, 0); + rs_set_device_option(rs_device_, RS_OPTION_COLOR_ENABLE_AUTO_WHITE_BALANCE, config.COLOR_ENABLE_AUTO_WHITE_BALANCE, 0); + + if(config.COLOR_ENABLE_AUTO_WHITE_BALANCE == 1) { + rs_set_device_option(rs_device_, RS_OPTION_COLOR_WHITE_BALANCE, config.COLOR_WHITE_BALANCE, 0); + } + + //R200 camera specific options + rs_set_device_option(rs_device_, RS_OPTION_R200_LR_AUTO_EXPOSURE_ENABLED, config.R200_LR_AUTO_EXPOSURE_ENABLED, 0); + + if(config.R200_LR_AUTO_EXPOSURE_ENABLED == 0) { + rs_set_device_option(rs_device_, RS_OPTION_R200_LR_EXPOSURE, config.R200_LR_EXPOSURE, 0); + } + + rs_set_device_option(rs_device_, RS_OPTION_R200_LR_GAIN, config.R200_LR_GAIN, 0); + rs_set_device_option(rs_device_, RS_OPTION_R200_EMITTER_ENABLED, config.R200_EMITTER_ENABLED, 0); + rs_set_device_option(rs_device_, RS_OPTION_R200_DISPARITY_MULTIPLIER, config.R200_DISPARITY_MULTIPLIER, 0); + + if(config.R200_LR_AUTO_EXPOSURE_ENABLED == 1) + { + if(config.R200_AUTO_EXPOSURE_TOP_EDGE >= depth_height_) { + config.R200_AUTO_EXPOSURE_TOP_EDGE = depth_height_ - 1; + } + if(config.R200_AUTO_EXPOSURE_BOTTOM_EDGE >= depth_height_) { + config.R200_AUTO_EXPOSURE_BOTTOM_EDGE = depth_height_ - 1; + } + if(config.R200_AUTO_EXPOSURE_LEFT_EDGE >= depth_width_) { + config.R200_AUTO_EXPOSURE_LEFT_EDGE = depth_width_ - 1; + } + if(config.R200_AUTO_EXPOSURE_RIGHT_EDGE >= depth_width_) { + config.R200_AUTO_EXPOSURE_RIGHT_EDGE = depth_width_ - 1; + } + edge_values[0] = config.R200_AUTO_EXPOSURE_LEFT_EDGE; + edge_values[1] = config.R200_AUTO_EXPOSURE_TOP_EDGE; + edge_values[2] = config.R200_AUTO_EXPOSURE_RIGHT_EDGE; + edge_values[3] = config.R200_AUTO_EXPOSURE_BOTTOM_EDGE; + + rs_set_device_options(rs_device_, edge_options, 4, edge_values, 0); + } + } + void RealsenseNodelet::check_error () { if (rs_error_) diff --git a/camera/src/realsense_camera_nodelet.h b/camera/src/realsense_camera_nodelet.h index 42a60cc69a..709e8d5258 100644 --- a/camera/src/realsense_camera_nodelet.h +++ b/camera/src/realsense_camera_nodelet.h @@ -60,6 +60,9 @@ #include #include +#include +#include + namespace realsense_camera { @@ -129,6 +132,14 @@ class RealsenseNodelet: public nodelet::Nodelet cv::Mat image_[STREAM_COUNT]; + rs_option edge_options[4] = { + RS_OPTION_R200_AUTO_EXPOSURE_LEFT_EDGE, + RS_OPTION_R200_AUTO_EXPOSURE_TOP_EDGE, + RS_OPTION_R200_AUTO_EXPOSURE_RIGHT_EDGE, + RS_OPTION_R200_AUTO_EXPOSURE_BOTTOM_EDGE + }; + double edge_values[4]; + sensor_msgs::CameraInfoPtr camera_info_ptr_[STREAM_COUNT]; sensor_msgs::CameraInfo * camera_info_[STREAM_COUNT]; image_transport::CameraPublisher camera_publisher_[STREAM_COUNT]; @@ -149,6 +160,7 @@ class RealsenseNodelet: public nodelet::Nodelet double min, max, step, value; }; std::vector options; + boost::shared_ptr> mReconfigureServer; // Member Functions. void check_error(); @@ -165,6 +177,7 @@ class RealsenseNodelet: public nodelet::Nodelet void getConfigValues(std::vector args); void setConfigValues(std::vector args, std::vector cam_options); bool getCameraSettings(realsense_camera::cameraConfiguration::Request & req, realsense_camera::cameraConfiguration::Response & res); + void configCallback(realsense_camera::camera_paramsConfig &config, uint32_t level); }; } From aeeddde6e1c8c68bf95a68a674e02e0bb9e55fc8 Mon Sep 17 00:00:00 2001 From: rjingar Date: Thu, 25 Feb 2016 12:25:54 -0800 Subject: [PATCH 032/124] Added dynamic reconfiguration section in README. Formatting in cfg file. Changed variable names to follow ROS coding standards. Modified CMakelists.txt file --- camera/CMakeLists.txt | 4 +- camera/README.md | 59 +++++++++++++++++++++---- camera/cfg/camera_params.cfg | 40 ++++++++--------- camera/src/realsense_camera_nodelet.cpp | 14 +++--- camera/src/realsense_camera_nodelet.h | 6 +-- 5 files changed, 81 insertions(+), 42 deletions(-) diff --git a/camera/CMakeLists.txt b/camera/CMakeLists.txt index 9b72272811..1d4f617504 100644 --- a/camera/CMakeLists.txt +++ b/camera/CMakeLists.txt @@ -54,15 +54,13 @@ target_link_libraries(realsense_camera_nodelet ${catkin_LIBRARIES} /usr/local/lib/librealsense.so ) -add_dependencies(realsense_camera_nodelet ${PROJECT_NAME}_gencfg) -add_dependencies(realsense_camera_nodelet realsense_camera_generate_messages_cpp) +add_dependencies(realsense_camera_nodelet realsense_camera_generate_messages_cpp ${PROJECT_NAME}_gencfg) add_executable(realsense_camera_test test/realsense_camera_test_node.cpp) target_link_libraries(realsense_camera_test ${catkin_LIBRARIES} ${GTEST_LIBRARIES} ) -add_dependencies(realsense_camera_test ${PROJECT_NAME}_gencfg) add_dependencies(realsense_camera_test realsense_camera_generate_messages_cpp) add_executable(realsense_camera_test_rgbd test/realsense_camera_test_rgbd_node.cpp) diff --git a/camera/README.md b/camera/README.md index e834cfe1ed..83ad8b6146 100644 --- a/camera/README.md +++ b/camera/README.md @@ -28,15 +28,6 @@ Sample launch files are available in camera/launch directory realsense_r200_rgbd.launch -Note: The camera does not provide hardware based depth registration/projector data. Hence the launch file "realsense_r200_rgbd.launch" will not generate data for the following topics: -/camera/depth_registered/hw_registered/image_rect_raw -/camera/depth_registered/points -/camera/depth_registered/hw_registered/image_rect -/camera/depth_registered/image -/camera/depth/disparity -/camera/depth_registered/disparity - - ### Intel® RealSense™ R200 Nodelet Publishing stream data from the Intel® RealSense™ R200 (DS4) camera @@ -135,6 +126,48 @@ Infrared2 camera get_settings (camera/get_settings) To get supported camera options with current value set. It returns string in options:value format where different options are seperated by semicolon. +####Dynamic Reconfiguration + List of dynamically configurable camera options: + + COLOR_BACKLIGHT_COMPENSATION + COLOR_BRIGHTNESS + COLOR_CONTRAST + COLOR_GAIN + COLOR_GAMMA + COLOR_HUE + COLOR_SATURATION + COLOR_SHARPNESS + COLOR_WHITE_BALANCE + COLOR_ENABLE_AUTO_WHITE_BALANCE + R200_LR_AUTO_EXPOSURE_ENABLED + R200_LR_GAIN + R200_LR_EXPOSURE + R200_EMITTER_ENABLED + R200_DISPARITY_MULTIPLIER + R200_AUTO_EXPOSURE_TOP_EDGE + R200_AUTO_EXPOSURE_BOTTOM_EDGE + R200_AUTO_EXPOSURE_LEFT_EDGE + R200_AUTO_EXPOSURE_RIGHT_EDGE + +Use rqt_reconfigure GUI to view and edit the parameters that are accessible via dynamic_reconfigure. + +Command to launch GUI: + + $ rosrun rqt_reconfigure rqt_reconfigure + +Change options commandline using following command: + + $ rosrun dynamic_reconfigure dynparam set /node parameter_name value + E.g. $ rosrun dynamic_reconfigure dynparam set /RealsenseNodelet COLOR_BACKLIGHT_COMPENSATION 2 + +Note: For Autoexposure EDGE parameters, max value will go only upto the bounds of the infrared image. +E.g. For 320x240 infrared image, valid values are within 0-319 and 0-239) + +To change EDGE parameters, R200_LR_AUTO_EXPOSURE_ENABLED should be enabled. +To set R200_LR_EXPOSURE, R200_LR_AUTO_EXPOSURE_ENABLED should be disabled. +To set COLOR_WHITE_BALANCE, COLOR_ENABLE_AUTO_WHITE_BALANCE should be disabled. + + ###Running the R200 nodelet Use the following command to launch the camera nodelet. You will notice the camera light up. @@ -225,4 +258,12 @@ Currently, the ROS camera nodelet only supports the following formats: * Depth stream: Y16 * Infrared stream: Y8 +Note: The camera does not provide hardware based depth registration/projector data. Hence the launch file "realsense_r200_rgbd.launch" will not generate data for the following topics: +/camera/depth_registered/hw_registered/image_rect_raw +/camera/depth_registered/points +/camera/depth_registered/hw_registered/image_rect +/camera/depth_registered/image +/camera/depth/disparity +/camera/depth_registered/disparity + diff --git a/camera/cfg/camera_params.cfg b/camera/cfg/camera_params.cfg index 95502ee366..7c38ddb934 100755 --- a/camera/cfg/camera_params.cfg +++ b/camera/cfg/camera_params.cfg @@ -6,25 +6,25 @@ from dynamic_reconfigure.parameter_generator_catkin import * gen = ParameterGenerator() -gen.add("COLOR_BACKLIGHT_COMPENSATION", int_t, 0, "Backlight Compensation", 1, 0, 4) -gen.add("COLOR_BRIGHTNESS", int_t, 0, "Brightness", 56, 0, 255) -gen.add("COLOR_CONTRAST", int_t, 0, "Contrast", 32, 16, 64) -gen.add("COLOR_GAIN", int_t, 0, "Gain", 32, 0, 256) -gen.add("COLOR_GAMMA", int_t, 0, "Gamma", 220, 100, 280) -gen.add("COLOR_HUE", int_t, 0, "Hue", 0, -2200, 2200) -gen.add("COLOR_SATURATION", int_t, 0, "Saturation", 128, 0, 255) -gen.add("COLOR_SHARPNESS", int_t, 0, "Sharpness", 0, 0, 7) -gen.add("COLOR_WHITE_BALANCE", int_t, 0, "White Balance", 6500, 2000, 8000) -gen.add("COLOR_ENABLE_AUTO_WHITE_BALANCE", int_t, 0, "Enable Auto White Balance", 1, 0, 1) -gen.add("R200_LR_AUTO_EXPOSURE_ENABLED", int_t, 0, "LR Auto Exposure Enabled", 0, 0, 1) -gen.add("R200_LR_GAIN", int_t, 0, "LR Gain", 400, 100, 6399) -gen.add("R200_LR_EXPOSURE", int_t, 0, "LR Exposure", 164, 1, 330) -gen.add("R200_EMITTER_ENABLED", int_t, 0, "Emitter Enabled", 1, 0, 1) -gen.add("R200_DISPARITY_MULTIPLIER", int_t, 0, "Disparity Multiplier", 32, 1, 1000) -gen.add("R200_AUTO_EXPOSURE_TOP_EDGE", int_t, 0, "Auto Exposure Top Edge", 0, 0, 479) -gen.add("R200_AUTO_EXPOSURE_BOTTOM_EDGE", int_t, 0, "Auto Exposure Bottom Edge", 479, 0, 479) -gen.add("R200_AUTO_EXPOSURE_LEFT_EDGE", int_t, 0, "Auto Exposure Left Edge", 0, 0, 639) -gen.add("R200_AUTO_EXPOSURE_RIGHT_EDGE", int_t, 0, "Auto Exposure Right Edge", 639, 0, 639) +# Name Type Level Description Default Min Max +gen.add("COLOR_BACKLIGHT_COMPENSATION", int_t, 0, "Backlight Compensation", 1, 0, 4) +gen.add("COLOR_BRIGHTNESS", int_t, 0, "Brightness", 56, 0, 255) +gen.add("COLOR_CONTRAST", int_t, 0, "Contrast", 32, 16, 64) +gen.add("COLOR_GAIN", int_t, 0, "Gain", 32, 0, 256) +gen.add("COLOR_GAMMA", int_t, 0, "Gamma", 220, 100, 280) +gen.add("COLOR_HUE", int_t, 0, "Hue", 0, -2200, 2200) +gen.add("COLOR_SATURATION", int_t, 0, "Saturation", 128, 0, 255) +gen.add("COLOR_SHARPNESS", int_t, 0, "Sharpness", 0, 0, 7) +gen.add("COLOR_WHITE_BALANCE", int_t, 0, "White Balance", 6500, 2000, 8000) +gen.add("COLOR_ENABLE_AUTO_WHITE_BALANCE", int_t, 0, "Enable Auto White Balance", 1, 0, 1) +gen.add("R200_LR_AUTO_EXPOSURE_ENABLED", int_t, 0, "LR Auto Exposure Enabled", 0, 0, 1) +gen.add("R200_LR_GAIN", int_t, 0, "LR Gain", 400, 100, 6399) +gen.add("R200_LR_EXPOSURE", int_t, 0, "LR Exposure", 164, 1, 330) +gen.add("R200_EMITTER_ENABLED", int_t, 0, "Emitter Enabled", 1, 0, 1) +gen.add("R200_DISPARITY_MULTIPLIER", int_t, 0, "Disparity Multiplier", 32, 1, 1000) +gen.add("R200_AUTO_EXPOSURE_TOP_EDGE", int_t, 0, "Auto Exposure Top Edge", 0, 0, 479) +gen.add("R200_AUTO_EXPOSURE_BOTTOM_EDGE", int_t, 0, "Auto Exposure Bottom Edge", 479, 0, 479) +gen.add("R200_AUTO_EXPOSURE_LEFT_EDGE", int_t, 0, "Auto Exposure Left Edge", 0, 0, 639) +gen.add("R200_AUTO_EXPOSURE_RIGHT_EDGE", int_t, 0, "Auto Exposure Right Edge", 639, 0, 639) exit(gen.generate(PACKAGE, "realsense_camera", "camera_params")) - diff --git a/camera/src/realsense_camera_nodelet.cpp b/camera/src/realsense_camera_nodelet.cpp index f045af4a7b..aa02445ae8 100644 --- a/camera/src/realsense_camera_nodelet.cpp +++ b/camera/src/realsense_camera_nodelet.cpp @@ -121,8 +121,8 @@ namespace realsense_camera get_options_service_ = nh.advertiseService (SETTINGS_SERVICE, &RealsenseNodelet::getCameraSettings, this); - mReconfigureServer.reset(new dynamic_reconfigure::Server(getPrivateNodeHandle())); - mReconfigureServer->setCallback(boost::bind(&RealsenseNodelet::configCallback, this, _1, _2)); + dynamic_reconf_server_.reset(new dynamic_reconfigure::Server(getPrivateNodeHandle())); + dynamic_reconf_server_->setCallback(boost::bind(&RealsenseNodelet::configCallback, this, _1, _2)); bool connected = false; @@ -186,12 +186,12 @@ namespace realsense_camera if(config.R200_AUTO_EXPOSURE_RIGHT_EDGE >= depth_width_) { config.R200_AUTO_EXPOSURE_RIGHT_EDGE = depth_width_ - 1; } - edge_values[0] = config.R200_AUTO_EXPOSURE_LEFT_EDGE; - edge_values[1] = config.R200_AUTO_EXPOSURE_TOP_EDGE; - edge_values[2] = config.R200_AUTO_EXPOSURE_RIGHT_EDGE; - edge_values[3] = config.R200_AUTO_EXPOSURE_BOTTOM_EDGE; + edge_values_[0] = config.R200_AUTO_EXPOSURE_LEFT_EDGE; + edge_values_[1] = config.R200_AUTO_EXPOSURE_TOP_EDGE; + edge_values_[2] = config.R200_AUTO_EXPOSURE_RIGHT_EDGE; + edge_values_[3] = config.R200_AUTO_EXPOSURE_BOTTOM_EDGE; - rs_set_device_options(rs_device_, edge_options, 4, edge_values, 0); + rs_set_device_options(rs_device_, edge_options_, 4, edge_values_, 0); } } diff --git a/camera/src/realsense_camera_nodelet.h b/camera/src/realsense_camera_nodelet.h index 709e8d5258..fffe5dcdf9 100644 --- a/camera/src/realsense_camera_nodelet.h +++ b/camera/src/realsense_camera_nodelet.h @@ -132,13 +132,13 @@ class RealsenseNodelet: public nodelet::Nodelet cv::Mat image_[STREAM_COUNT]; - rs_option edge_options[4] = { + rs_option edge_options_[4] = { RS_OPTION_R200_AUTO_EXPOSURE_LEFT_EDGE, RS_OPTION_R200_AUTO_EXPOSURE_TOP_EDGE, RS_OPTION_R200_AUTO_EXPOSURE_RIGHT_EDGE, RS_OPTION_R200_AUTO_EXPOSURE_BOTTOM_EDGE }; - double edge_values[4]; + double edge_values_[4]; sensor_msgs::CameraInfoPtr camera_info_ptr_[STREAM_COUNT]; sensor_msgs::CameraInfo * camera_info_[STREAM_COUNT]; @@ -160,7 +160,7 @@ class RealsenseNodelet: public nodelet::Nodelet double min, max, step, value; }; std::vector options; - boost::shared_ptr> mReconfigureServer; + boost::shared_ptr> dynamic_reconf_server_; // Member Functions. void check_error(); From 77d731943566f5ce72a9b441f92391d5467ba786 Mon Sep 17 00:00:00 2001 From: rjingar Date: Thu, 25 Feb 2016 14:40:41 -0800 Subject: [PATCH 033/124] Resolved Service call failed issue --- camera/src/realsense_camera_nodelet.cpp | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/camera/src/realsense_camera_nodelet.cpp b/camera/src/realsense_camera_nodelet.cpp index aa02445ae8..0e902b035e 100644 --- a/camera/src/realsense_camera_nodelet.cpp +++ b/camera/src/realsense_camera_nodelet.cpp @@ -120,9 +120,8 @@ namespace realsense_camera } get_options_service_ = nh.advertiseService (SETTINGS_SERVICE, &RealsenseNodelet::getCameraSettings, this); - - dynamic_reconf_server_.reset(new dynamic_reconfigure::Server(getPrivateNodeHandle())); - dynamic_reconf_server_->setCallback(boost::bind(&RealsenseNodelet::configCallback, this, _1, _2)); + + dynamic_reconf_server_.reset(new dynamic_reconfigure::Server(getPrivateNodeHandle())); bool connected = false; @@ -140,6 +139,8 @@ namespace realsense_camera { ros::shutdown (); } + + dynamic_reconf_server_->setCallback(boost::bind(&RealsenseNodelet::configCallback, this, _1, _2)); } /* From de8d62db1f67c63df37f44a9d429fa9b0e98af29 Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Thu, 25 Feb 2016 16:26:55 -0800 Subject: [PATCH 034/124] Updated README to correct filenames. --- camera/README.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/camera/README.md b/camera/README.md index 83ad8b6146..966ab93d38 100644 --- a/camera/README.md +++ b/camera/README.md @@ -157,7 +157,7 @@ Command to launch GUI: Change options commandline using following command: - $ rosrun dynamic_reconfigure dynparam set /node parameter_name value + $ rosrun dynamic_reconfigure dynparam set / E.g. $ rosrun dynamic_reconfigure dynparam set /RealsenseNodelet COLOR_BACKLIGHT_COMPENSATION 2 Note: For Autoexposure EDGE parameters, max value will go only upto the bounds of the infrared image. @@ -229,7 +229,7 @@ Using rostest command with test files Using rosrun command - $ roslaunch realsense_camera realsense_r200_launch_manual.launch + $ roslaunch realsense_camera realsense_r200_nodelet_standalone_manual.launch $ rosrun realsense_camera realsense_camera_test E.g. rosrun realsense_camera realsense_camera_test enable_depth 1 depth_encoding 16UC1 depth_height 360 depth_width 480 depth_step 960 enable_color 1 color_encoding rgb8 color_height 480 color_width 640 color_step 1920 From 0ff3e4ba515e8838719aa2d1f5e25bba90a4e3d8 Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Thu, 25 Feb 2016 16:29:45 -0800 Subject: [PATCH 035/124] Updated README to fix angle bracket issue. --- camera/README.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/camera/README.md b/camera/README.md index 966ab93d38..ccbee57463 100644 --- a/camera/README.md +++ b/camera/README.md @@ -8,8 +8,8 @@ * Make sure that the software stack is installed properly and that the camera is working. This can be checked by connecting the camera to a USB3 port and running the "cpp-capture" sample program in the "librealsense/bin" folder. If this does not work, you should first fix this issue before continuing with the ROS integration. * Make sure "/usr/local/lib" is set in your "LD_LIBRARY_PATH". -* Copy the librealsense header files folder "librealsense/include/librealsense" to "/usr/local/include". - +* Copy the librealsense header files folder "librealsense/include/librealsense" to "/usr/local/include". + E.g. sudo cp -r /include/librealsense /usr/local/include From 7baf02457dafffdd9a2f4192c4567c570ad33249 Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Thu, 25 Feb 2016 16:35:51 -0800 Subject: [PATCH 036/124] Updated README to fix angle bracket issue. --- camera/README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/camera/README.md b/camera/README.md index ccbee57463..880e221eb6 100644 --- a/camera/README.md +++ b/camera/README.md @@ -10,7 +10,7 @@ If this does not work, you should first fix this issue before continuing with th * Make sure "/usr/local/lib" is set in your "LD_LIBRARY_PATH". * Copy the librealsense header files folder "librealsense/include/librealsense" to "/usr/local/include". - E.g. sudo cp -r /include/librealsense /usr/local/include + E.g. sudo cp -r \/include/librealsense /usr/local/include #####Building package: From b9a68b0d32ef5c9263b91357a719ba866b955a39 Mon Sep 17 00:00:00 2001 From: Rajvi Jingar Date: Fri, 26 Feb 2016 14:47:13 -0600 Subject: [PATCH 037/124] Update camera_params.cfg Changed MAX value for R200_LR_EXPOSURE setting --- camera/cfg/camera_params.cfg | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/camera/cfg/camera_params.cfg b/camera/cfg/camera_params.cfg index 7c38ddb934..ce1d2376f7 100755 --- a/camera/cfg/camera_params.cfg +++ b/camera/cfg/camera_params.cfg @@ -19,7 +19,7 @@ gen.add("COLOR_WHITE_BALANCE", int_t, 0, "White Balance gen.add("COLOR_ENABLE_AUTO_WHITE_BALANCE", int_t, 0, "Enable Auto White Balance", 1, 0, 1) gen.add("R200_LR_AUTO_EXPOSURE_ENABLED", int_t, 0, "LR Auto Exposure Enabled", 0, 0, 1) gen.add("R200_LR_GAIN", int_t, 0, "LR Gain", 400, 100, 6399) -gen.add("R200_LR_EXPOSURE", int_t, 0, "LR Exposure", 164, 1, 330) +gen.add("R200_LR_EXPOSURE", int_t, 0, "LR Exposure", 164, 1, 164) gen.add("R200_EMITTER_ENABLED", int_t, 0, "Emitter Enabled", 1, 0, 1) gen.add("R200_DISPARITY_MULTIPLIER", int_t, 0, "Disparity Multiplier", 32, 1, 1000) gen.add("R200_AUTO_EXPOSURE_TOP_EDGE", int_t, 0, "Auto Exposure Top Edge", 0, 0, 479) From 885c94d0ee7e4acd7db273a9d59196e257eb5aa4 Mon Sep 17 00:00:00 2001 From: Rajvi Jingar Date: Fri, 26 Feb 2016 14:48:38 -0600 Subject: [PATCH 038/124] Update realsense_camera_nodelet.cpp changed COLOR_ENABLE_AUTO_WHITE_BALANCE condition check to set COLOR_WHITE_BALANCE --- camera/src/realsense_camera_nodelet.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/camera/src/realsense_camera_nodelet.cpp b/camera/src/realsense_camera_nodelet.cpp index 0e902b035e..506868e43d 100644 --- a/camera/src/realsense_camera_nodelet.cpp +++ b/camera/src/realsense_camera_nodelet.cpp @@ -158,7 +158,7 @@ namespace realsense_camera rs_set_device_option(rs_device_, RS_OPTION_COLOR_SHARPNESS, config.COLOR_SHARPNESS, 0); rs_set_device_option(rs_device_, RS_OPTION_COLOR_ENABLE_AUTO_WHITE_BALANCE, config.COLOR_ENABLE_AUTO_WHITE_BALANCE, 0); - if(config.COLOR_ENABLE_AUTO_WHITE_BALANCE == 1) { + if(config.COLOR_ENABLE_AUTO_WHITE_BALANCE == 0) { rs_set_device_option(rs_device_, RS_OPTION_COLOR_WHITE_BALANCE, config.COLOR_WHITE_BALANCE, 0); } From bbd3a450bed6bcec798dec7ea987ecc50a5f02bb Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Fri, 26 Feb 2016 14:57:30 -0800 Subject: [PATCH 039/124] RAR-180-dynamic-reconfigure-unit-test intial commit. --- camera/CMakeLists.txt | 2 +- camera/test/realsense_camera_test_node.cpp | 29 ++++++++++++++++--- .../test/realsense_r200_settings_dynconf.test | 14 +++++++++ 3 files changed, 40 insertions(+), 5 deletions(-) create mode 100644 camera/test/realsense_r200_settings_dynconf.test diff --git a/camera/CMakeLists.txt b/camera/CMakeLists.txt index 1d4f617504..29dc548ee9 100644 --- a/camera/CMakeLists.txt +++ b/camera/CMakeLists.txt @@ -61,7 +61,7 @@ target_link_libraries(realsense_camera_test ${catkin_LIBRARIES} ${GTEST_LIBRARIES} ) -add_dependencies(realsense_camera_test realsense_camera_generate_messages_cpp) +add_dependencies(realsense_camera_test realsense_camera_generate_messages_cpp ${PROJECT_NAME}_gencfg) add_executable(realsense_camera_test_rgbd test/realsense_camera_test_rgbd_node.cpp) target_link_libraries(realsense_camera_test_rgbd diff --git a/camera/test/realsense_camera_test_node.cpp b/camera/test/realsense_camera_test_node.cpp index 6379c9ead7..94a5907c41 100644 --- a/camera/test/realsense_camera_test_node.cpp +++ b/camera/test/realsense_camera_test_node.cpp @@ -8,12 +8,12 @@ 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. - 2. Redistributions in binary form must reproduce the above copyright notice, - this list of conditions and the following disclaimer in the documentation + 2. Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. - 3. Neither the name of the copyright holder nor the names of its contributors - may be used to endorse or promote products derived from this software without + 3. Neither the name of the copyright holder nor the names of its contributors + may be used to endorse or promote products derived from this software without specific prior written permission. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" @@ -410,6 +410,27 @@ TEST (RealsenseTests, testTransforms) EXPECT_TRUE(tf_listener.canTransform (COLOR_DEF_FRAME,COLOR_OPTICAL_DEF_FRAME, ros::Time::now())); } +TEST (RealsenseTests, testDynamicReconfigure) +{ + stringstream settings_ss (srv.response.configuration_str); + string setting; + string setting_name; + string setting_value; + + while (getline (settings_ss, setting, ';')) + { + stringstream setting_ss (setting); + getline (setting_ss, setting_name, ':'); + setting_value = (setting.substr (setting.rfind (":") + 1)); + if (config_args.find (setting_name) != config_args.end ()) + { + int actual_value = atoi (setting_value.c_str ()); + int expected_value = atoi (config_args.at (setting_name).c_str ()); + EXPECT_EQ (expected_value, actual_value); + } + } +} + void fillConfigMap(int argc, char **argv) { std::vector < std::string > args; diff --git a/camera/test/realsense_r200_settings_dynconf.test b/camera/test/realsense_r200_settings_dynconf.test new file mode 100644 index 0000000000..46cbb04e6c --- /dev/null +++ b/camera/test/realsense_r200_settings_dynconf.test @@ -0,0 +1,14 @@ + + + + + + + + + + + \ No newline at end of file From 7016e8d511baf32b97e59be834e1928a3a6a1166 Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Fri, 26 Feb 2016 17:16:24 -0800 Subject: [PATCH 040/124] Updated README file for transform frames, removed non-required license file, removed incorrectly commented code. --- camera/README.md | 9 +- ...ra Alpha, Beta, Prototype Site License.htm | 395 ------------------ camera/test/realsense_camera_test_node.cpp | 85 ++-- .../test/realsense_r200_settings_dynconf.test | 14 - 4 files changed, 50 insertions(+), 453 deletions(-) delete mode 100644 camera/licenses/Intel OBL RealSense 3D Camera Alpha, Beta, Prototype Site License.htm delete mode 100644 camera/test/realsense_r200_settings_dynconf.test diff --git a/camera/README.md b/camera/README.md index 880e221eb6..dd11f9bd43 100644 --- a/camera/README.md +++ b/camera/README.md @@ -64,6 +64,12 @@ Infrared2 camera camera/infrared2/camera_info Calibration data +#### Transform Frames + The following command creates a pdf file that describes the transforms generated by the camera nodelet. You may refer to the [ROS tf wiki](http://wiki.ros.org/tf) for more commands. + + rosrun tf tf_monitor + + ####Parameters mode (string, default: preset) @@ -124,7 +130,8 @@ Infrared2 camera ####Services get_settings (camera/get_settings) - To get supported camera options with current value set. It returns string in options:value format where different options are seperated by semicolon. + +To get supported camera options with current value set. It returns string in options:value format where different options are seperated by semicolon. ####Dynamic Reconfiguration List of dynamically configurable camera options: diff --git a/camera/licenses/Intel OBL RealSense 3D Camera Alpha, Beta, Prototype Site License.htm b/camera/licenses/Intel OBL RealSense 3D Camera Alpha, Beta, Prototype Site License.htm deleted file mode 100644 index 0479020e0f..0000000000 --- a/camera/licenses/Intel OBL RealSense 3D Camera Alpha, Beta, Prototype Site License.htm +++ /dev/null @@ -1,395 +0,0 @@ - - - - - - - - - - - -
- -
- - - - - - - - -
-

INTEL SOFTWARE LICENSE - AGREEMENT (Alpha, Beta, Prototype Site License) for Intel RealSense 3D - Camera

-

By clicking the Accept - button, I signify that I have read and accept the terms below.

-
-

Top of - Form

-
-
-

Bottom - of Form

-
-
- - - - - - - -
-

IMPORTANT - - READ BEFORE COPYING, INSTALLING OR USING.

-
-

Do not use or load software from this site or any associated - materials (collectively, the "Software") until you have carefully - read the following terms and conditions. By loading or using the Software, - you agree to the terms of this Agreement. If you do not wish to so agree, - do not download, install or use the Software.

-

Please Also Note:

-
    -
  • The - Software has to be installed to use the Intel RealSense 3D Camera.
  • -
  • In the - event of a conflict between the terms of the software license - agreement posted on this site and the terms of the software license - agreement delivered with the Software, the terms of the software - license agreement delivered with the Software will control.
  • -
  • If the - Software contains pre-release alpha, beta or prototype code, the - Software may not be fully functional and Intel may substantially - modify the Software in producing any final version.  Intel can - provide no assurance that it will ever produce or make generally - available a final or production version of the Software.
  • -
  • If the - Software contains final or production code, the Software may be - subject to the terms of a license agreement delivered with such - Software.  In such case, the terms of the license agreement - delivered with the Software will control.
  • -
-
-
-

 

-

LICENSE.  Intel hereby grants you a - limited, nontransferable, non-sublicenseable, nonexclusive, royalty-free, - fully-paid license under Intels copyrights to use the Software with Intel 3D - Camera hardware only and solely for your organizations internal evaluation - and testing, subject to these conditions:

-

1. - You may not copy, modify, rent, sell, distribute, externally display, - externally perform or transfer any part of the Software except as provided in - this Agreement, and you agree to prevent unauthorized copying of the - Software.

-

2. - You may not reverse engineer, decompile, or disassemble the Software.

-

3. - You may not sublicense the Software.

-

4. - The Software may include portions offered on terms in addition to those set - out here, as set out in a license accompanying those portions.

-

5. - You may not subject the Software, in whole or in part, to any license - obligations of Open Source Software including without limitation combining or - distributing the Software with Open Source Software in a manner that subjects - the Software or any portion of the Software provided by Intel hereunder to - any license obligations of such Open Source Software. "Open Source - Software" means any software that requires as a condition of use, - modification and/or distribution of such software that such software or other - software incorporated into, derived from or distributed with such software - (a) be disclosed or distributed in source code form; or (b) be licensed by - the user to third parties for the purpose of making and/or distributing - derivative works; or (c) be redistributable at no charge. Open Source - Software includes, without limitation, software licensed or distributed under - any of the following licenses or distribution models, or licenses or - distribution models substantially similar to any of the following: (a) GNUs - General Public License (GPL) or Lesser/Library GPL (LGPL), (b) the Artistic - License (e.g., PERL), (c) the Mozilla Public License, (d) the Netscape Public - License, (e) the Sun Community Source License (SCSL), (f) the Sun Industry - Source License (SISL), (g) the Apache Software license and (h) the Common Public - License (CPL).

-

 

-

FEEDBACK.  This Agreement does NOT - obligate you to provide Intel with comments or suggestions regarding the - Software.  However, should you provide Intel with comments or - suggestions for the modification, correction, improvement or enhancement of - (a) the Software or (b) the 3D camera, other products or processes which work - or interact with the Software, you grant to Intel and/or Intels licensors - (where your comments or suggestions relate to their respective applications - that may be included in the Software or the 3D camera) a non-exclusive, - irrevocable, worldwide, royalty-free license, with the right to sublicense to - Intels licensees and customers and/or Intels licensors licensees and - customers, under your intellectual property rights, the rights to use and - disclose such comments and suggestions in any manner Intel or Intels - licensors choose, and to display, perform, copy, make, have made, use, sell, - and otherwise dispose of Intels and Intels licensors and their licensees - products embodying such comments and suggestions in any manner and via any - media Intel and/or Intels licensors choose, without reference to the source.

-

 

-

OWNERSHIP OF SOFTWARE AND COPYRIGHTS. - Title to all copies of the Software remains with Intel or its suppliers. The - Software is copyrighted and protected by the laws of the United States and - other countries, and international treaty provisions. You may not remove any - copyright notices from the Software. Intel may make changes to the Software, - or to items referenced therein, at any time without notice, but is not - obligated to support, update or provide training for the Software. Except as - otherwise expressly provided, Intel grants no express or implied right under - Intel patents, copyrights, trademarks, or other intellectual property rights. -

-

 

-

LIMITED MEDIA WARRANTY.  If the - Software has been delivered by Intel on physical media, Intel warrants the - media to be free from material physical defects for a period of ninety days - after delivery by Intel. If such a defect is found, return the media to Intel - for replacement or alternate delivery of the Software as Intel may select.

-

 

-

EXCLUSION OF OTHER WARRANTIES. - EXCEPT AS PROVIDED ABOVE, THE SOFTWARE IS PROVIDED "AS IS" WITHOUT - ANY EXPRESS OR IMPLIED WARRANTY OF ANY KIND INCLUDING WARRANTIES OF - MERCHANTABILITY, NONINFRINGEMENT, OR FITNESS FOR A PARTICULAR PURPOSE.  - Intel does not warrant or assume responsibility for the accuracy or - completeness of any information, text, graphics, links or other items - contained within the Software.

-

 

-

LIMITATION OF LIABILITY. IN NO EVENT SHALL - INTEL OR ITS SUPPLIERS BE LIABLE FOR ANY DAMAGES WHATSOEVER (INCLUDING, - WITHOUT LIMITATION, LOST PROFITS, BUSINESS INTERRUPTION OR LOST INFORMATION) - ARISING OUT OF THE USE OF OR INABILITY TO USE THE SOFTWARE, EVEN IF INTEL HAS - BEEN ADVISED OF THE POSSIBILITY OF SUCH DAMAGES. SOME JURISDICTIONS PROHIBIT - EXCLUSION OR LIMITATION OF LIABILITY FOR IMPLIED WARRANTIES OR CONSEQUENTIAL - OR INCIDENTAL DAMAGES, SO THE ABOVE LIMITATION MAY NOT APPLY TO YOU. YOU MAY - ALSO HAVE OTHER LEGAL RIGHTS THAT VARY FROM JURISDICTION TO - JURISDICTION.  THE SOFTWARE LICENSED HEREUNDER IS NOT DESIGNED OR - INTENDED FOR USE IN ANY MEDICAL, LIFE SAVING OR LIFE SUSTAINING SYSTEMS, - TRANSPORTATION SYSTEMS, NUCLEAR SYSTEMS, OR FOR ANY OTHER MISSION CRITICAL - APPLICATION IN WHICH THE FAILURE OF THE SOFTWARE COULD LEAD TO PERSONAL - INJURY OR DEATH. YOU SHALL INDEMNIFY AND HOLD INTEL AND THE INTEL PARTIES - HARMLESS AGAINST ALL CLAIMS, COSTS, DAMAGES, AND EXPENSES, AND REASONABLE - ATTORNEY FEES ARISING OUT OF, DIRECTLY OR INDIRECTLY, THE DISTRIBUTION OF THE - SOFTWARE AND ANY CLAIM OF PRODUCT LIABILITY, PERSONAL INJURY OR DEATH - ASSOCIATED WITH ANY UNINTENDED USE, EVEN IF SUCH CLAIM ALLEGES THAT AN INTEL - PARTY WAS NEGLIGENT REGARDING THE DESIGN OR MANUFACTURE OF THE SOFTWARE. THE - LIMITED REMEDIES, WARRANTY DISCLAIMER AND LIMITED LIABILITY ARE FUNDAMENTAL - ELEMENTS OF THE BASIS OF THE BARGAIN BETWEEN INTEL AND YOU. INTEL WOULD NOT - BE ABLE TO PROVIDE THE SOFTWARE WITHOUT SUCH LIMITATIONS.

-

 

-

TERMINATION OF THIS AGREEMENT. - Intel may terminate this Agreement at any time if you violate its terms. Upon - termination, you will immediately destroy the Software or return all copies - of the Software to Intel (including providing certification of such destruction - back to Intel).  In the event of termination of this Agreement, all - licenses granted to you hereunder shall immediately terminate.

-

 

-

APPLICABLE LAWS. Claims arising under - this Agreement shall be governed by the laws of Delaware, excluding its principles - of conflict of laws and the United Nations Convention on Contracts for the - Sale of Goods. You may not export the Software in violation of applicable - export laws and regulations.

-

 

-

GOVERNMENT RESTRICTED RIGHTS. - The Software is provided with "RESTRICTED RIGHTS." Use, duplication - or disclosure by the government is subject to restrictions as set forth in - FAR52.227-14 and DFAR252.227-7013 et seq. or its successor. Use of the - Software by the government constitutes acknowledgment of Intel's proprietary - rights therein.  Contractor or Manufacturer is Intel Corporation, 2200 - Mission College Blvd., Santa Clara, CA 95052.

-

 

-

CONFIDENTIALITY.  You shall not - disclose the terms or existence of this Agreement or use Intel's name in any - publications, advertisements, or other announcements without Intel's prior - written consent. You do not have any rights to use any Intel trademarks or - logos.

-

 

-

ASSIGNMENT.  You may not - delegate, assign or transfer this Agreement, the license(s) granted or any of - your rights or duties hereunder, expressly, by implication, by operation of - law, by way of merger (regardless of whether you are the surviving entity) or - acquisition, or otherwise and any attempt to do so, without Intels express - prior written consent, shall be null and void. Intel may assign this - Agreement, and its rights and obligations hereunder, in its sole discretion.

-

 

-

ENTIRE AGREEMENT. The terms and conditions - of this Agreement constitutes the entire agreement between the parties with - respect to the subject matter hereof, and merges and supersedes all prior, - contemporaneous agreements, understandings, negotiations and discussions. - Neither of the parties hereto shall be bound by any conditions, definitions, - warranties, understandings or representations with respect to the subject - matter hereof other than as expressly provided for herein. Intel is not - obligated under any other agreements unless they are in writing and signed by - an authorized representative of Intel.

-

 

-

NO AGENCY. Nothing contained herein - shall be construed as creating any agency, employment relationship, - partnership, principal-agent or other form of joint enterprise between the - parties.

-

 

-

SEVERABILITY. In the event that any - provision of this Agreement shall be unenforceable or invalid under any - applicable law or be so held by an applicable court decision, such - unenforceability or invalidity shall not render this Agreement unenforceable - or invalid as a whole, and, in such event, such provision shall be changed - and interpreted so as to best accomplish the objectives of such unenforceable - or invalid provision within the limits of applicable law or applicable court - decisions.

-

 

-

WAIVER. The failure of either party to - require performance by the other party of any provision hereof shall not - affect the full right to require such performance at any time thereafter; nor - shall the waiver by either party of a breach of any provision hereof be taken - or held to be a waiver of the provision itself.

-
-

 

-
- -
- -

 

- -

 

- -
- - - - diff --git a/camera/test/realsense_camera_test_node.cpp b/camera/test/realsense_camera_test_node.cpp index 94a5907c41..7f84367a89 100644 --- a/camera/test/realsense_camera_test_node.cpp +++ b/camera/test/realsense_camera_test_node.cpp @@ -125,34 +125,33 @@ void imageDepthCallback(const sensor_msgs::ImageConstPtr & msg, const sensor_msg depth_recv = true; } -/* - void pcCallback (const sensor_msgs::PointCloud2ConstPtr pc) - { - pcl::PointCloud < pcl::PointXYZRGB > pointcloud; - pcl::fromROSMsg (*pc, pointcloud); - - long pc_depth_total = 0; - int pc_depth_count = 0; - for (int i = 0; i < pointcloud.width * pointcloud.height; ++i) - { - pcl::PointXYZRGB point = pointcloud.points[i]; - float pc_depth = (float) std::ceil (point.z); - if (0 < pc_depth <= 10) - { - pc_depth_total += pc_depth; - pc_depth_count++; - } - } - - - if (pc_depth_count != 0) - { - pc_depth_avg = pc_depth_total / pc_depth_count; - } - - pc_recv = true; - } - */ + + void pcCallback(const sensor_msgs::PointCloud2ConstPtr pc) +{ + pcl::PointCloud < pcl::PointXYZRGB > pointcloud; + pcl::fromROSMsg(*pc, pointcloud); + + long pc_depth_total = 0; + int pc_depth_count = 0; + for (unsigned int i = 0; i < pointcloud.width * pointcloud.height; ++i) + { + pcl::PointXYZRGB point = pointcloud.points[i]; + float pc_depth = (float) std::ceil(point.z); + if ((0 < pc_depth) && (pc_depth <= R200_DEPTH_MAX)) + { + pc_depth_total += pc_depth; + pc_depth_count++; + } + } + + if (pc_depth_count != 0) + { + pc_depth_avg = pc_depth_total / pc_depth_count; + } + + pc_recv = true; +} + void imageColorCallback(const sensor_msgs::ImageConstPtr & msg, const sensor_msgs::CameraInfoConstPtr & info_msg) { @@ -362,21 +361,21 @@ TEST (RealsenseTests, testInfrared2CameraInfo) } } -/* + TEST (RealsenseTests, testPointCloud) - { - if (enable_depth) - { - ROS_INFO_STREAM ("RealSense Camera - pc_depth_avg: " << pc_depth_avg); - EXPECT_TRUE (pc_depth_avg > 0); - EXPECT_TRUE (pc_recv); - } - else - { - EXPECT_FALSE (pc_recv); - } - } - */ +{ + if (enable_depth) + { + ROS_INFO_STREAM ("RealSense Camera - pc_depth_avg: " << pc_depth_avg); + EXPECT_TRUE (pc_depth_avg > 0); + EXPECT_TRUE (pc_recv); + } + else + { + EXPECT_FALSE (pc_recv); + } +} + TEST (RealsenseTests, testCameraSettings) { @@ -537,7 +536,7 @@ int main(int argc, char **argv) camera_subscriber[3] = it.subscribeCamera(IR2_TOPIC, 1, imageInfrared2Callback, 0); } - //m_sub_pc = nh.subscribe (PC_TOPIC, 1, pcCallback); + m_sub_pc = nh.subscribe (PC_TOPIC, 1, pcCallback); ros::ServiceClient client = nh.serviceClient < realsense_camera::cameraConfiguration > (SETTINGS_SERVICE); client.call(srv); diff --git a/camera/test/realsense_r200_settings_dynconf.test b/camera/test/realsense_r200_settings_dynconf.test deleted file mode 100644 index 46cbb04e6c..0000000000 --- a/camera/test/realsense_r200_settings_dynconf.test +++ /dev/null @@ -1,14 +0,0 @@ - - - - - - - - - - - \ No newline at end of file From 20f8a4ec389bf24511427f5b0e2226bc1eb80502 Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Sat, 27 Feb 2016 19:22:32 -0800 Subject: [PATCH 041/124] add enable_tf flag to allow for disabling publish transform --- .../realsense_r200_nodelet.launch.xml} | 13 +++++- ...ense_r200_nodelet_standalone_preset.launch | 8 ++-- camera/launch/realsense_r200_rgbd.launch | 14 ++++--- camera/src/realsense_camera_nodelet.cpp | 42 ++++++++++++++----- camera/src/realsense_camera_nodelet.h | 12 +++--- 5 files changed, 63 insertions(+), 26 deletions(-) rename camera/launch/{realsense_r200_nodelet.launch => includes/realsense_r200_nodelet.launch.xml} (78%) diff --git a/camera/launch/realsense_r200_nodelet.launch b/camera/launch/includes/realsense_r200_nodelet.launch.xml similarity index 78% rename from camera/launch/realsense_r200_nodelet.launch rename to camera/launch/includes/realsense_r200_nodelet.launch.xml index 410fe91ca8..2fac0ac011 100644 --- a/camera/launch/realsense_r200_nodelet.launch +++ b/camera/launch/includes/realsense_r200_nodelet.launch.xml @@ -1,7 +1,10 @@ - + + + + @@ -14,6 +17,11 @@ Else "enable_depth_ir" will take the value of "enable_depth" --> + + + + @@ -25,7 +33,8 @@ rgb_frame_id $(arg rgb_frame_id) enable_depth $(arg enable_depth_ir) enable_color $(arg enable_color) - enable_pointcloud $(arg enable_pointcloud)"> + enable_pointcloud $(arg enable_pointcloud) + enable_tf $(arg enable_tf)"> diff --git a/camera/launch/realsense_r200_nodelet_standalone_preset.launch b/camera/launch/realsense_r200_nodelet_standalone_preset.launch index 39ef3a29ab..f39e99e09c 100644 --- a/camera/launch/realsense_r200_nodelet_standalone_preset.launch +++ b/camera/launch/realsense_r200_nodelet_standalone_preset.launch @@ -3,16 +3,18 @@ - + + + enable_color $(arg enable_color) + enable_pointcloud $(arg enable_pointcloud) + enable_tf $(arg enable_tf)"> diff --git a/camera/launch/realsense_r200_rgbd.launch b/camera/launch/realsense_r200_rgbd.launch index f0b45fc499..d0e207d34c 100644 --- a/camera/launch/realsense_r200_rgbd.launch +++ b/camera/launch/realsense_r200_rgbd.launch @@ -18,8 +18,10 @@ + tree. Useful if you are playing back recorded raw data from a bag, or are + supplying a more accurate tf tree from calibration. --> + @@ -50,17 +52,17 @@ - + file="$(find realsense_camera)/launch/includes/realsense_r200_nodelet.launch.xml"> - + + - + - + diff --git a/camera/src/realsense_camera_nodelet.cpp b/camera/src/realsense_camera_nodelet.cpp index 506868e43d..ccab900bcc 100644 --- a/camera/src/realsense_camera_nodelet.cpp +++ b/camera/src/realsense_camera_nodelet.cpp @@ -8,12 +8,12 @@ 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. - 2. Redistributions in binary form must reproduce the above copyright notice, - this list of conditions and the following disclaimer in the documentation + 2. Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. - 3. Neither the name of the copyright holder nor the names of its contributors - may be used to endorse or promote products derived from this software without + 3. Neither the name of the copyright holder nor the names of its contributors + may be used to endorse or promote products derived from this software without specific prior written permission. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" @@ -47,7 +47,11 @@ namespace realsense_camera RealsenseNodelet::~RealsenseNodelet () { device_thread_->join (); - transform_thread_->join(); + + if (enable_tf_ == true) + { + transform_thread_->join(); + } // Stop device. if (is_device_started_ == true) @@ -78,6 +82,7 @@ namespace realsense_camera enable_depth_ = ENABLE_DEPTH; enable_color_ = ENABLE_COLOR; enable_pointcloud_ = ENABLE_PC; + enable_tf_ = ENABLE_TF; is_device_started_ = false; camera_configuration_ = getMyArgv (); @@ -120,8 +125,8 @@ namespace realsense_camera } get_options_service_ = nh.advertiseService (SETTINGS_SERVICE, &RealsenseNodelet::getCameraSettings, this); - - dynamic_reconf_server_.reset(new dynamic_reconfigure::Server(getPrivateNodeHandle())); + + dynamic_reconf_server_.reset(new dynamic_reconfigure::Server(getPrivateNodeHandle())); bool connected = false; @@ -132,15 +137,20 @@ namespace realsense_camera // Start working thread. device_thread_ = boost::shared_ptr < boost::thread > (new boost::thread (boost::bind (&RealsenseNodelet::devicePoll, this))); - transform_thread_ = - boost::shared_ptr < boost::thread > (new boost::thread (boost::bind (&RealsenseNodelet::publishTransforms, this))); + + if (enable_tf_ == true) + { + transform_thread_ = + boost::shared_ptr < boost::thread > (new boost::thread (boost::bind (&RealsenseNodelet::publishTransforms, this))); + } + } else { ros::shutdown (); } - dynamic_reconf_server_->setCallback(boost::bind(&RealsenseNodelet::configCallback, this, _1, _2)); + dynamic_reconf_server_->setCallback(boost::bind(&RealsenseNodelet::configCallback, this, _1, _2)); } /* @@ -479,6 +489,18 @@ namespace realsense_camera } } + if (config_.find ("enable_tf") != config_.end ()) + { + if (strcmp((config_.at ("enable_tf").c_str ()),"true") == 0) + { + enable_tf_ = true; + } + else + { + enable_tf_ = false; + } + } + if (config_.find ("camera") != config_.end ()) { camera_ = config_.at ("camera").c_str (); diff --git a/camera/src/realsense_camera_nodelet.h b/camera/src/realsense_camera_nodelet.h index fffe5dcdf9..d6b356963c 100644 --- a/camera/src/realsense_camera_nodelet.h +++ b/camera/src/realsense_camera_nodelet.h @@ -8,12 +8,12 @@ 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. - 2. Redistributions in binary form must reproduce the above copyright notice, - this list of conditions and the following disclaimer in the documentation + 2. Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. - 3. Neither the name of the copyright holder nor the names of its contributors - may be used to endorse or promote products derived from this software without + 3. Neither the name of the copyright holder nor the names of its contributors + may be used to endorse or promote products derived from this software without specific prior written permission. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" @@ -86,6 +86,7 @@ class RealsenseNodelet: public nodelet::Nodelet const bool ENABLE_DEPTH = true; const bool ENABLE_COLOR = true; const bool ENABLE_PC = true; + const bool ENABLE_TF = true; const uint32_t SERIAL_NUMBER = 0xFFFFFFFF; const rs_format DEPTH_FORMAT = RS_FORMAT_Z16; const rs_format COLOR_FORMAT = RS_FORMAT_RGB8; @@ -126,6 +127,7 @@ class RealsenseNodelet: public nodelet::Nodelet bool enable_color_; bool enable_depth_; bool enable_pointcloud_; + bool enable_tf_; std::vector camera_configuration_; std::string camera_ = "R200"; const uint16_t *image_depth16_; @@ -138,7 +140,7 @@ class RealsenseNodelet: public nodelet::Nodelet RS_OPTION_R200_AUTO_EXPOSURE_RIGHT_EDGE, RS_OPTION_R200_AUTO_EXPOSURE_BOTTOM_EDGE }; - double edge_values_[4]; + double edge_values_[4]; sensor_msgs::CameraInfoPtr camera_info_ptr_[STREAM_COUNT]; sensor_msgs::CameraInfo * camera_info_[STREAM_COUNT]; From 652ad9b109c5459efe49040f68397dde54ebacda Mon Sep 17 00:00:00 2001 From: Matthew Hansen Date: Sun, 28 Feb 2016 12:24:23 -0800 Subject: [PATCH 042/124] add enable_tf flag to manual launch file --- camera/launch/realsense_r200_nodelet_standalone_manual.launch | 1 + 1 file changed, 1 insertion(+) diff --git a/camera/launch/realsense_r200_nodelet_standalone_manual.launch b/camera/launch/realsense_r200_nodelet_standalone_manual.launch index 519fbcf0b1..f07e0fe0a4 100644 --- a/camera/launch/realsense_r200_nodelet_standalone_manual.launch +++ b/camera/launch/realsense_r200_nodelet_standalone_manual.launch @@ -8,6 +8,7 @@ + From c6d6bd43171073de83a3db08144ea66e4a6afd9a Mon Sep 17 00:00:00 2001 From: Matthew Hansen Date: Sun, 28 Feb 2016 12:25:05 -0800 Subject: [PATCH 043/124] add realsense_r200_navigation launch file --- .../launch/realsense_r200_navigation.launch | 20 +++++++++++++++++++ camera/ros-realsense-nav/turtlebot/README.md | 8 ++++---- 2 files changed, 24 insertions(+), 4 deletions(-) create mode 100644 camera/launch/realsense_r200_navigation.launch diff --git a/camera/launch/realsense_r200_navigation.launch b/camera/launch/realsense_r200_navigation.launch new file mode 100644 index 0000000000..f32469053d --- /dev/null +++ b/camera/launch/realsense_r200_navigation.launch @@ -0,0 +1,20 @@ + + + + + + + + + + + + + + diff --git a/camera/ros-realsense-nav/turtlebot/README.md b/camera/ros-realsense-nav/turtlebot/README.md index 0c34102b54..d44d6c12c7 100644 --- a/camera/ros-realsense-nav/turtlebot/README.md +++ b/camera/ros-realsense-nav/turtlebot/README.md @@ -39,13 +39,13 @@ alias setkinect='export TURTLEBOT_3D_SENSOR=kinect && export TURTLEBOT_STACKS=he ## B - Mapping -The only difference from the kinect version of the navigation stack is that you need to start the camera driver before the navigation: `roslaunch realsense_camera realsense_r200_nodelet_standalone_preset.launch`. +The only difference from the kinect version of the navigation stack is that you need to start the camera driver before the navigation: `roslaunch realsense_camera realsense_r200_navigation.launch`. So, the normal flow would be : ```bash roslaunch turtlebot_bringup minimal.launch -roslaunch realsense_camera realsense_r200_nodelet_standalone_preset.launch +roslaunch realsense_camera realsense_r200_navigation.launch roslaunch realsense_navigation gmapping.launch roslaunch turtlebot_rviz_launchers view_navigation.launch ``` @@ -69,7 +69,7 @@ Once you have a map, you can start the navigation with the following commands ```bash roslaunch turtlebot_bringup minimal.launch -roslaunch realsense_camera realsense_r200_nodelet_standalone_preset.launch +roslaunch realsense_camera realsense_r200_navigation.launch roslaunch realsense_navigation navigation_demo.launch map:= ``` @@ -83,7 +83,7 @@ So we first need to start the turtlebot (+ the teleop of your choice) and the ca ```bash roslaunch turtlebot_bringup minimal.launch -roslaunch realsense_camera realsense_r200_nodelet_standalone_preset.launch +roslaunch realsense_camera realsense_r200_navigation.launch ``` Then, we will store the relevent topics in a bag file: From 798f0030821f4a1336a642da14be958ba6434cea Mon Sep 17 00:00:00 2001 From: Matthew Hansen Date: Sun, 28 Feb 2016 14:04:27 -0800 Subject: [PATCH 044/124] change realsense_frame to camera_link in transform --- camera/src/realsense_camera_nodelet.h | 6 +++--- camera/test/realsense_camera_test_node.h | 6 +++--- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/camera/src/realsense_camera_nodelet.h b/camera/src/realsense_camera_nodelet.h index d6b356963c..dd27b3f8a1 100644 --- a/camera/src/realsense_camera_nodelet.h +++ b/camera/src/realsense_camera_nodelet.h @@ -92,11 +92,11 @@ class RealsenseNodelet: public nodelet::Nodelet const rs_format COLOR_FORMAT = RS_FORMAT_RGB8; const rs_format IR1_FORMAT = RS_FORMAT_Y8; const rs_format IR2_FORMAT = RS_FORMAT_Y8; - const char *BASE_DEF_FRAME = "realsense_frame"; + const char *BASE_DEF_FRAME = "camera_link"; const char *DEPTH_DEF_FRAME = "camera_depth_frame"; - const char *COLOR_DEF_FRAME = "camera_color_frame"; + const char *COLOR_DEF_FRAME = "camera_rgb_frame"; const char *DEPTH_OPTICAL_DEF_FRAME = "camera_depth_optical_frame"; - const char *COLOR_OPTICAL_DEF_FRAME = "camera_color_optical_frame"; + const char *COLOR_OPTICAL_DEF_FRAME = "camera_rgb_optical_frame"; const char *IR1_DEF_FRAME = "camera_infrared_optical_frame"; const char *IR2_DEF_FRAME = "camera_infrared2_optical_frame"; const char *DEPTH_TOPIC = "camera/depth/image_raw"; diff --git a/camera/test/realsense_camera_test_node.h b/camera/test/realsense_camera_test_node.h index 7233b020ec..e2e9a5be8b 100644 --- a/camera/test/realsense_camera_test_node.h +++ b/camera/test/realsense_camera_test_node.h @@ -61,11 +61,11 @@ const char *SETTINGS_SERVICE = "camera/get_settings"; const char *R200 = "R200"; const int R200_DEPTH_MAX = 10000; -const char *BASE_DEF_FRAME = "realsense_frame"; +const char *BASE_DEF_FRAME = "camera_link"; const char *DEPTH_DEF_FRAME = "camera_depth_frame"; -const char *COLOR_DEF_FRAME = "camera_color_frame"; +const char *COLOR_DEF_FRAME = "camera_rgb_frame"; const char *DEPTH_OPTICAL_DEF_FRAME = "camera_depth_optical_frame"; -const char *COLOR_OPTICAL_DEF_FRAME = "camera_color_optical_frame"; +const char *COLOR_OPTICAL_DEF_FRAME = "camera_rgb_optical_frame"; //utest commandline args int color_height_exp = 0; From 2f19a75f73fac0814a3565600cbd8e87c5936391 Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Mon, 29 Feb 2016 11:06:48 -0800 Subject: [PATCH 045/124] Updated document fixes. --- .gitignore | 5 + camera/.cproject | 70 ------- camera/.project | 71 ------- .../org.eclipse.cdt.managedbuilder.core.prefs | 14 -- camera/README.md | 4 +- camera/docs/RealSense-ROS-R200-nodelet.html | 113 ----------- camera/docs/RealSense-ROS-R200-nodelet.md | 180 ------------------ camera/docs/realsenseRvizScreenshot.png | Bin 921129 -> 0 bytes camera/licenses/{ReadMe.txt => License.txt} | 0 camera/licenses/Licenses.txt | 3 - .../turtlebot/README.md | 0 .../turtlebot/doc/img/bag_screen.png | Bin .../turtlebot/doc/img/mapping_screen.png | Bin .../turtlebot/doc/img/screen-ds4-nav.png | Bin .../turtlebot/doc/style-doc.css | 0 .../turtlebot/install_realsense_navigation.sh | 0 .../turtlebot/launch/amcl.launch | 0 .../turtlebot/launch/gmapping.launch | 0 .../turtlebot/launch/navigation_demo.launch | 0 .../launch/realsense_robot_description.launch | 0 .../turtlebot/launch/simulate_mapping.launch | 0 .../turtlebot/package.xml | 0 .../custom_costmap_params.yaml | 0 .../kobuki_minimal_r200.urdf.xacro | 0 .../robot_description/meshes/sensors/r200.dae | 0 .../meshes/sensors/r200_entire.dae | 0 .../meshes/sensors/r200_entire/texture0.jpg | Bin .../meshes/sensors/r200_only.dae | 0 .../robot_description/r200.launch.xml | 0 .../turtlebot_library_extended.urdf.xacro | 0 .../urdf/sensors/r200.urdf.xacro | 0 .../urdf/stacks/minimal.urdf.xacro | 0 .../turtlebot/rviz/navigation_r200.rviz | 0 .../rviz/navigation_r200_without_depth.rviz | 0 camera/package.xml | 3 +- 35 files changed, 10 insertions(+), 453 deletions(-) delete mode 100644 camera/.cproject delete mode 100644 camera/.project delete mode 100644 camera/.settings/org.eclipse.cdt.managedbuilder.core.prefs delete mode 100644 camera/docs/RealSense-ROS-R200-nodelet.html delete mode 100644 camera/docs/RealSense-ROS-R200-nodelet.md delete mode 100644 camera/docs/realsenseRvizScreenshot.png rename camera/licenses/{ReadMe.txt => License.txt} (100%) delete mode 100644 camera/licenses/Licenses.txt rename camera/{ros-realsense-nav => navigation}/turtlebot/README.md (100%) rename camera/{ros-realsense-nav => navigation}/turtlebot/doc/img/bag_screen.png (100%) rename camera/{ros-realsense-nav => navigation}/turtlebot/doc/img/mapping_screen.png (100%) rename camera/{ros-realsense-nav => navigation}/turtlebot/doc/img/screen-ds4-nav.png (100%) rename camera/{ros-realsense-nav => navigation}/turtlebot/doc/style-doc.css (100%) rename camera/{ros-realsense-nav => navigation}/turtlebot/install_realsense_navigation.sh (100%) rename camera/{ros-realsense-nav => navigation}/turtlebot/launch/amcl.launch (100%) rename camera/{ros-realsense-nav => navigation}/turtlebot/launch/gmapping.launch (100%) rename camera/{ros-realsense-nav => navigation}/turtlebot/launch/navigation_demo.launch (100%) rename camera/{ros-realsense-nav => navigation}/turtlebot/launch/realsense_robot_description.launch (100%) rename camera/{ros-realsense-nav => navigation}/turtlebot/launch/simulate_mapping.launch (100%) rename camera/{ros-realsense-nav => navigation}/turtlebot/package.xml (100%) rename camera/{ros-realsense-nav => navigation}/turtlebot/robot_description/custom_costmap_params.yaml (100%) rename camera/{ros-realsense-nav => navigation}/turtlebot/robot_description/kobuki_minimal_r200.urdf.xacro (100%) rename camera/{ros-realsense-nav => navigation}/turtlebot/robot_description/meshes/sensors/r200.dae (100%) rename camera/{ros-realsense-nav => navigation}/turtlebot/robot_description/meshes/sensors/r200_entire.dae (100%) rename camera/{ros-realsense-nav => navigation}/turtlebot/robot_description/meshes/sensors/r200_entire/texture0.jpg (100%) rename camera/{ros-realsense-nav => navigation}/turtlebot/robot_description/meshes/sensors/r200_only.dae (100%) rename camera/{ros-realsense-nav => navigation}/turtlebot/robot_description/r200.launch.xml (100%) rename camera/{ros-realsense-nav => navigation}/turtlebot/robot_description/turtlebot_library_extended.urdf.xacro (100%) rename camera/{ros-realsense-nav => navigation}/turtlebot/robot_description/urdf/sensors/r200.urdf.xacro (100%) rename camera/{ros-realsense-nav => navigation}/turtlebot/robot_description/urdf/stacks/minimal.urdf.xacro (100%) rename camera/{ros-realsense-nav => navigation}/turtlebot/rviz/navigation_r200.rviz (100%) rename camera/{ros-realsense-nav => navigation}/turtlebot/rviz/navigation_r200_without_depth.rviz (100%) diff --git a/.gitignore b/.gitignore index 6259391948..1f5220ba76 100644 --- a/.gitignore +++ b/.gitignore @@ -8,3 +8,8 @@ # Ignore all Linux Editor revision save files *~ +# Ignore all hidden files +.project +.cproject +.settings + diff --git a/camera/.cproject b/camera/.cproject deleted file mode 100644 index ca7ca6b28a..0000000000 --- a/camera/.cproject +++ /dev/null @@ -1,70 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/camera/.project b/camera/.project deleted file mode 100644 index da529c3a53..0000000000 --- a/camera/.project +++ /dev/null @@ -1,71 +0,0 @@ - - - realsense_ros - - - - - - org.eclipse.cdt.managedbuilder.core.genmakebuilder - clean,full,incremental, - - - ?name? - - - - org.eclipse.cdt.make.core.append_environment - true - - - org.eclipse.cdt.make.core.buildArguments - - - - org.eclipse.cdt.make.core.buildCommand - make - - - org.eclipse.cdt.make.core.buildLocation - ${workspace_loc:/ds4_camera/Default} - - - org.eclipse.cdt.make.core.contents - org.eclipse.cdt.make.core.activeConfigSettings - - - org.eclipse.cdt.make.core.enableAutoBuild - false - - - org.eclipse.cdt.make.core.enableCleanBuild - true - - - org.eclipse.cdt.make.core.enableFullBuild - true - - - org.eclipse.cdt.make.core.stopOnError - true - - - org.eclipse.cdt.make.core.useDefaultBuildCmd - true - - - - - org.eclipse.cdt.managedbuilder.core.ScannerConfigBuilder - full,incremental, - - - - - - org.eclipse.cdt.core.cnature - org.eclipse.cdt.core.ccnature - org.eclipse.cdt.managedbuilder.core.managedBuildNature - org.eclipse.cdt.managedbuilder.core.ScannerConfigNature - - diff --git a/camera/.settings/org.eclipse.cdt.managedbuilder.core.prefs b/camera/.settings/org.eclipse.cdt.managedbuilder.core.prefs deleted file mode 100644 index 820b971dc1..0000000000 --- a/camera/.settings/org.eclipse.cdt.managedbuilder.core.prefs +++ /dev/null @@ -1,14 +0,0 @@ -eclipse.preferences.version=1 -environment/buildEnvironmentInclude/0.451674452/CPATH/delimiter=\: -environment/buildEnvironmentInclude/0.451674452/CPATH/operation=replace -environment/buildEnvironmentInclude/0.451674452/CPATH/value=/home/turtlebot/workspace/3AM/ROS_Nodes/catkin_tb/devel/include\:/opt/ros/indigo/include -environment/buildEnvironmentInclude/0.451674452/CPLUS_INCLUDE_PATH/delimiter=\: -environment/buildEnvironmentInclude/0.451674452/CPLUS_INCLUDE_PATH/operation=remove -environment/buildEnvironmentInclude/0.451674452/C_INCLUDE_PATH/delimiter=\: -environment/buildEnvironmentInclude/0.451674452/C_INCLUDE_PATH/operation=remove -environment/buildEnvironmentInclude/0.451674452/append=true -environment/buildEnvironmentInclude/0.451674452/appendContributed=true -environment/buildEnvironmentLibrary/0.451674452/LIBRARY_PATH/delimiter=\: -environment/buildEnvironmentLibrary/0.451674452/LIBRARY_PATH/operation=remove -environment/buildEnvironmentLibrary/0.451674452/append=true -environment/buildEnvironmentLibrary/0.451674452/appendContributed=true diff --git a/camera/README.md b/camera/README.md index dd11f9bd43..1e9b549837 100644 --- a/camera/README.md +++ b/camera/README.md @@ -22,11 +22,13 @@ Successful execution of command will build target “realsense_camera_nodelet Sample launch files are available in camera/launch directory +realsense_r200_rgbd.launch + realsense_r200_nodelet_standalone_preset.launch realsense_r200_nodelet_standalone_manual.launch -realsense_r200_rgbd.launch +realsense_r200_nodelet_standalone_settings.launch ### Intel® RealSense™ R200 Nodelet Publishing stream data from the Intel® RealSense™ R200 (DS4) camera diff --git a/camera/docs/RealSense-ROS-R200-nodelet.html b/camera/docs/RealSense-ROS-R200-nodelet.html deleted file mode 100644 index 2d9668a531..0000000000 --- a/camera/docs/RealSense-ROS-R200-nodelet.html +++ /dev/null @@ -1,113 +0,0 @@ -

Intel RealSense Technology - ROS Integration

-

(ROS Indigo + Ubuntu 14.04 [64-bit])

-

Installation

-
Getting the camera to work on Linux
-

Please make sure that you have a working camera and that the software stack is installed properly. This can be checked by connecting the camera (to a USB3 port) and running one of the provided librealsense samples. If this does not work, you should first fix this issue before continuing with the ROS integration.

-
Building package:
-
    -
  • Follow the steps in the README.md file of the ros repository. Setup ROS and create a local catkin workspace.
  • -
  • To compile just realsense package, instead of catkin_make, execute following command catkin_make --pkg realsense
  • -
-

Successful execution of command will build target “r200_camera_nodelet”

-

Sample launch files are available in realsense/launch directory

-

realsense_r200_launch_preset.launch

-

realsense_r200_launch_manual.launch

-

Intel RealSense R200 Nodelet

-

Publishing stream data from the Intel RealSense R200 (DS4) camera

-

Subscribed Topics

-
None
-

Publisehd Topics

-

Color camera

-
camera/color/image_raw (sensor_msgs/Image)
-    Color rectified image. RGB format.
-camera/color/camera_info
-    Calibration data
-

Depth camera

-
camera/depth/image_raw (sensor_msgs/Image)
-    uint16 depths in mm
-camera/depth/camera_info
-    Calibration data
-camera/depth/points (sensor_msgs/PointCloud2)
-    Registered XYZRGB point cloud.
-

Infrared camera

-
camera/infrared1/image_raw (sensor_msgs/Image)
-camera/infrared1/camera_info
-    Calibration data
-

Infrared2 camera

-
camera/infrared2/image_raw (sensor_msgs/Image)
-camera/infrared2/camera_info
-    Calibration data
-

Parameters

-
Mode (string, default: preset)
-Specify mode to start camera streams with. Preset mode starts all streams with defaults values for each stream’s width/height and FPS. In Manual mode, camera streams will be set with resolution and FPS values passed.
-cHeight (int, default: 480)
-    Specify the color camera height resolution.
-cWidth (int, default: 640)
-    Specify the color camera width resolution.
-dHeight (int, default: 360)
-    Specify the depth camera height resolution.
-dWidth (int, default: 480)
-    Specify the depth camera width resolution.
-cFPS (int, default: 60)
-    Specify the color camera FPS
-dFPS (int, default: 60)
-    Specify the depth camera FPS
-enableDepth (bool, default: 1) 
-    Specify if to enable or not the depth camera. 1 is true. 0 is false.
-enableColor (bool, default: 1) 
-    Specify if to enable or not the color camera. 1 is true. 0 is false.
-enablePointCloud (bool, default: 1) 
-    Specify if to enable or not the point cloud camera. 1 is true. 0 is false.
-Supported options: Here are r200 camera supported options that can be set
-    COLOR_BACKLIGHT_COMPENSATION : [0, 4]
-    COLOR_BRIGHTNESS : [0, 255]
-    COLOR_CONTRAST : [16, 64]
-    COLOR_EXPOSURE : [0, 0]
-    COLOR_GAIN : [0, 256]
-    COLOR_GAMMA : [100, 280]
-    COLOR_HUE : [-2200, 2200]
-    COLOR_SATURATION : [0, 255]
-    COLOR_SHARPNESS : [0, 7]
-    COLOR_WHITE_BALANCE : [2000, 8000]
-    COLOR_ENABLE_AUTO_EXPOSURE : [0, 0]
-    COLOR_ENABLE_AUTO_WHITE_BALANCE : [0, 1]
-    R200_LR_AUTO_EXPOSURE_ENABLED : [0, 1]
-    R200_LR_GAIN : [100, 1600]
-    R200_LR_EXPOSURE : [0, 333]
-    R200_EMITTER_ENABLED : [0, 1]
-    R200_DEPTH_CONTROL_PRESET : [0, 5]
-    R200_DEPTH_UNITS : [1, 2147483647]
-    R200_DEPTH_CLAMP_MIN : [0, 65535]
-    R200_DEPTH_CLAMP_MAX : [0, 65535]
-    R200_DISPARITY_MULTIPLIER : [1, 1000]
-    R200_DISPARITY_SHIFT : [0, 0] 
-

Services

-
None
-

Running the R200 nodelet

-

Simply type:

-
$ roslaunch realsense realsense_r200_launch.launch
-

This will launch the camera nodelet. You will see the camera lights up.

-

For color, infrared1 and infrared2 streams, you can open RVIZ and load the published topics.

-

You can also open RVIZ and load the provided RVIZ configuration file: realsenseRvizConfiguration.rviz.

-

Other commands to view streams:

-
    -
  • For Color stream

    -

    $ rosrun image_view image_view image:=/camera/color/image_raw

  • -
  • For depth stream

  • -
-

Verified data and other info by rostopic echo command for image_raw and camera_info.

-
$ rostopic echo /camera/depth/image_raw
-$ rostopic echo /camera/depth/camera_info
-
    -
  • For pointcloud
  • -
-

To view it in rviz, set camera_depth_optical_frame using following command:

-
$ rosrun tf static_transform_publisher 0.0 0.0 0.0 0.0 0.0 0.0 map camera_depth_optical_frame 100
-

To view it using image_view:

-
$ rosrun pcl_ros convert_pointcloud_to_image input:=/camera/depth/points output:=/my_image
-$ rosrun image_view image_view image:=/my_image
-

Tech and dependencies * librealsense.so

-

System: * Linux 14.04+ * ROS Indigo * R200 (DS4) camera

-

** The ROS integration has been tested on a 64bit machine with Linux 14.04 (Trusty) and ROS Indigo.

-

Limitations:

-

Currently camera ROS node supports following formats * Color stream: RGB8 * Depth stream: Y16 * Infrared stream: Y8

diff --git a/camera/docs/RealSense-ROS-R200-nodelet.md b/camera/docs/RealSense-ROS-R200-nodelet.md deleted file mode 100644 index 3f82ce9f53..0000000000 --- a/camera/docs/RealSense-ROS-R200-nodelet.md +++ /dev/null @@ -1,180 +0,0 @@ -#Intel® RealSense™ Technology - ROS Integration - -###(ROS Indigo + Ubuntu 14.04 [64-bit]) -###Installation -#####Getting the camera to work on Linux - -* Clone the source from the librealsense git repository https://github.intel.com/PerCSystemsEngineering/librealsense. -* Follow the instructions at https://github.intel.com/PerCSystemsEngineering/librealsense/blob/master/doc/installation.md. -* Make sure that the software stack is installed properly and that the camera is working. This can be checked by connecting the camera to a USB3 port and running the "cpp-capture" sample program in the "librealsense/bin" folder. -If this does not work, you should first fix this issue before continuing with the ROS integration. -* Make sure /usr/local/lib is in your LD__LIBRARY_PATH. - -#####Building package: - -* Follow the steps in the README.md file of the ros repository. Setup ROS and create a local catkin workspace. -* To compile just realsense package, instead of catkin_make, execute following command - catkin_make --pkg realsense - -Successful execution of command will build target “r200_camera_nodelet” - -Sample launch files are available in realsense/launch directory - -realsense_r200_launch_preset.launch - -realsense_r200_launch_manual.launch - -realsense_r200_launch_settings.launch - -### Intel® RealSense™ R200 Nodelet -Publishing stream data from the Intel® RealSense™ R200 (DS4) camera - -#### Subscribed Topics - None - -#### Published Topics - -Color camera - - camera/color/image_raw (sensor_msgs/Image) - Color rectified image. RGB format. - camera/color/camera_info - Calibration data - -Depth camera - - camera/depth/image_raw (sensor_msgs/Image) - uint16 depths in mm - camera/depth/camera_info - Calibration data - camera/depth/points (sensor_msgs/PointCloud2) - Registered XYZRGB point cloud. - -Infrared1 camera - - camera/infrared1/image_raw (sensor_msgs/Image) - camera/infrared1/camera_info - Calibration data - -Infrared2 camera - - camera/infrared2/image_raw (sensor_msgs/Image) - camera/infrared2/camera_info - Calibration data - -####Parameters - - mode (string, default: preset) - Specify the mode to start camera streams. Mode comprises of height, width and fps. - Preset mode enables default values whereas Manual mode enables the specified parameter values. - color_height (int, default: 480) - Specify the color camera height resolution. - color_width (int, default: 640) - Specify the color camera width resolution. - depth_height (int, default: 360) - Specify the depth camera height resolution. - depth_width (int, default: 480) - Specify the depth camera width resolution. - depth_fps (int, default: 60) - Specify the color camera FPS - depth_fps (int, default: 60) - Specify the depth camera FPS - enable_depth (bool, default: 1) - Specify if to enable or not the depth camera. 1 is true. 0 is false. - enable_color (bool, default: 1) - Specify if to enable or not the color camera. 1 is true. 0 is false. - enable_pointcloud (bool, default: 1) - Specify if to enable or not the point cloud camera. 1 is true. 0 is false. - camera (string, default: "R200") - Specify the camera name. - Supported options: Here are r200 camera supported options that can be set - COLOR_BACKLIGHT_COMPENSATION : [0, 4] - COLOR_BRIGHTNESS : [0, 255] - COLOR_CONTRAST : [16, 64] - COLOR_EXPOSURE : [0, 0] - COLOR_GAIN : [0, 256] - COLOR_GAMMA : [100, 280] - COLOR_HUE : [-2200, 2200] - COLOR_SATURATION : [0, 255] - COLOR_SHARPNESS : [0, 7] - COLOR_WHITE_BALANCE : [2000, 8000] - COLOR_ENABLE_AUTO_EXPOSURE : [0, 0] - COLOR_ENABLE_AUTO_WHITE_BALANCE : [0, 1] - R200_LR_AUTO_EXPOSURE_ENABLED : [0, 1] - R200_LR_GAIN : [100, 1600] - R200_LR_EXPOSURE : [0, 333] - R200_EMITTER_ENABLED : [0, 1] - R200_DEPTH_CONTROL_PRESET : [0, 5] - R200_DEPTH_UNITS : [1, 2147483647] - R200_DEPTH_CLAMP_MIN : [0, 65535] - R200_DEPTH_CLAMP_MAX : [0, 65535] - R200_DISPARITY_MULTIPLIER : [1, 1000] - R200_DEPTH_CONTROL_ESTIMATE_MEDIAN_DECREMENT : [0 - 255] - R200_DEPTH_CONTROL_ESTIMATE_MEDIAN_INCREMENT : [0 - 255] - R200_DEPTH_CONTROL_MEDIAN_THRESHOLD : [0 - 1023] - R200_DEPTH_CONTROL_SCORE_MINIMUM_THRESHOLD : [0 - 1023] - R200_DEPTH_CONTROL_SCORE_MAXIMUM_THRESHOLD : [0 - 1023] - R200_DEPTH_CONTROL_TEXTURE_COUNT_THRESHOLD : [0 - 31] - R200_DEPTH_CONTROL_TEXTURE_DIFFERENCE_THRESHOLD : [0 - 1023] - R200_DEPTH_CONTROL_SECOND_PEAK_THRESHOLD : [0 - 1023] - R200_DEPTH_CONTROL_NEIGHBOR_THRESHOLD : [0 - 1023] - R200_DEPTH_CONTROL_LR_THRESHOLD : [0 - 2047] - -####Services - get_settings (camera/get_settings) - To get supported camera options with current value set. It returns string in options:value format where different options are seperated by semicolon. - - -###Running the R200 nodelet - -Type the following to launch the camera nodelet. You will notice the camera light up. - - $ roslaunch realsense realsense_r200_launch_preset.launch - -View using RVIZ: - -For color, infrared1 and infrared2 streams, you can open RVIZ and load the published topics. -For the point cloud steam, before loading its corresponding topic, set the camera_depth_optical_frame using following command: - - $ rosrun tf static_transform_publisher 0.0 0.0 0.0 0.0 0.0 0.0 map camera_depth_optical_frame 100 - -You can also open RVIZ and load the provided RVIZ configuration file: realsenseRvizConfiguration.rviz. -![](docs/realsenseRvizScreenshot.png) - -View using other commands: -* For color stream - - $ rosrun image_view image_view image:=/camera/color/image_raw - -* For depth stream - - $ rostopic echo /camera/depth/image_raw - - $ rostopic echo /camera/depth/camera_info - -* For pointcloud - - $ rosrun pcl_ros convert_pointcloud_to_image input:=/camera/depth/points output:=/my_image - - $ rosrun image_view image_view image:=/my_image - -* For viewing supported camera settings with current values: - - $ rosservice call /camera/get_settings - -Tech and dependencies -* librealsense.so - -System: -* Linux 14.04+ -* ROS Indigo -* R200 (DS4) camera - -** The ROS integration has been tested on a 64bit machine with Linux 14.04 (Trusty) and ROS Indigo. - -###Limitations: -Currently camera ROS node supports following formats -* Color stream: RGB8 -* Depth stream: Y16 -* Infrared stream: Y8 - diff --git a/camera/docs/realsenseRvizScreenshot.png b/camera/docs/realsenseRvizScreenshot.png deleted file mode 100644 index 40e3d8663f7e769d7007c06cfc05b2914701d71c..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 921129 zcmZsCcQjmW_jc6i-4JC2i4vnl@6me~o#?&S(TOr*FoZx*!aq zm(TOQ-~0T2@AG|soORYYYu1|k-uK?uwfD96d84DHOiVyW@ZiA%VpSCdy$27lj~_h1 zD#gRSe}hL>{O$gR;j5=C_n>B!Vdwq<+fi0i_Q8XC7~!=w&iymKmx_t+g9j9Te_a?$ z4ou(&5AI4;6=V&-mV0>*b6*ZzoYg+Pn5W)je3$HJY!x`WWG&H2h{s|xJ!1x%>9A2I zOJ8c9?r1q%nhy{M?9ttHjtS&E?RQI5N}Gmd-5hS@hkVNw^DUF=z8X%nIo=!r2acG% z7IIx4oI6|UZU1vXuw>R^8XB>c*OGjAI`2ua6ug_n3P%sRMj&@O^xx-e@sLkKr z$u8O9995pw&lk(4u>@-^ly~eMbzxv#TCaaWweB^j^E-KUvl21& zg(I#HZ*EhVx(=8oCWY=alSeD>@Ppg8BGU3#{R9`c7;m(KgU4h*8M{BLsjnM%+sEb` z>?wuaz)U&9?mfwj^L4&k0rj58n@Kax?u5;r%UV}~FY0}_w0`_BwA!kvo@sUNwAyV> zdQB<}XIJPt``LM1QWXYM>}jcY;3j-+0q@uxVTCtd{$bkK5Bw;1MIPL~>2!Z>jq7JB zH(oA^gs11%h~4k|!qev@B=tJ9{rD^*A^+Qt?&SLc&6y}Efx>;@~eoofrvW(j;qDRQ}p++ zi;}CG-Ji7phR(&2%d=&vzAL7x3*BUCqoesX$iXS(ewm(c@>j22Cnlxta!#nq^F=SS zncjDobPF)K8HdDF&kJ8O&Nq8rOEe$MJUKnys%faUSuPvd9SBJKM6$85@$uuw$l~T^ zKu$|&q+@;<=1@&1oqidh$WM*gVK|p%0i)_fgDpOMeIl`n@5`AFUjmwc?PRhE~>qS~GAP8u*8>Fc`?sI&Sl zI9wp`GSpJY^OC&AM36>(bF}BJ^JHDP^+?iTqe2P8u*P+UdPQ4mv z__f=0)%A@GKGL7RlvD-_8P*G@z&O}C_+O^`cL-lBM+vntMf*2=Yv9&d2tEF6gUro( znkm$YCs0nEFg7cY01M^i80|YTiOrOVAaEGt-Z^qAI+)y~ri{%L@qMqtZ3ouVi~0;$b0eaqFi)0JPa0Xb~EX%Q9gx}NPE85=n9 zOZp3U{xAI8-_|1_`6rbn)>8Xj9iFi)GBT9Dj_(rkKno+8rjNIm@}-|L`8oouM{_AO zvZNo0DeipX`T7D?^)*wx1-o?5QnD2LSWT@i#n`|!K~Z15Ur1n+3a=i9K&g!6NGak$ z7y?wSNfHPf_)9YtTPW&bGPAbHV_BxpcfNR^w%evAg5ruG4e zGPCVfcfc0_fC|6p_opligxA(^mfUo@Rj?{^*#^zyh;MfMV?byyVVOoRe8NV9D?es+ zf`LlQQ5#-!C|2cMnuc@TIi%?IzE!&gY?NN$uaIe*nhNP_Kmwtb49=&`wzVB^`#|*t z1N_pkSUCVz$J)XT!}Topp1+Kd2)x#;|602b@kT74;lP6#Cewk_^}pc$-)p}<=%M=w z>qWTvK2IymlxP_uOqN=qUHT0`v=6jY#FlbonMY3a@h~SVw!B`@7=FgtcT@?mIlBJ( zr9ks)z%F7SQ!gF1`c=%rhMtrw&r%MxS@MAoR^#~8`%__)6Gel-Th6|L)vMer{eJW# z{aL6dox@n+)r1g3tp};N;p5}u3B?8Dep?JrHGa||`}$UT1Hcgq; zb@d&G3SAuhyjKOb3;V#2mHLVSw(uIfPF-3QV|14(Ks;Ig&PvHydQ&qG)GrM9X?e$DXK?dijt#`8Gi)2D*5Ccszt7juSkkB@0 zmQx`ckJo+`oJcRgK)I^K!YV|b=4*03M8z`qeQcVM#P_8B?#Z6}m$P45)4#78XfF`H zPyfxm|8bOexoA2~aj`n^jRehbOkEm%d)hoq;PA>`Vib+EQ_j1wjm?3lSNjykgFn4bS!Y z++D~WGu$`a7M)%^Qj#HC{uW~_tRW8r2t)5U&+{$LtW(ozu(CigN&ul*XkGa~ zgXvD9ZfzQ-D=Nk)X_0I5>qjURl|6y3bFeIPf^Q?gqY`tO_K2)^IBr84rEYc(=GNNT zYL2o8rezmS^OXb3`LfC4;Z$Nf&O~M6nqF|Uhoh36FCGT(h3rXVGa2Ju5mTaP!xVeIxuR#2CcV#VcFwo+Lm9$-fL$TKg16s~^tiXZ z;rON{>m1HZz@EWU>lb%e11;dg)mJ0*LKb)cmk_3uC9sVw?1Cw+% zt%Fgs$mxa_%QJ>>{R}bbfN| zz$Cw@vvl*jtU4o;sCma%Zz{yrQuA_RD*;cfE@KQpU)lg^j=V2Sdl`m#7-HH6eEAb5 z{I1WfGpR)Aob??Z2kJ4rrz$UWa>;1r{NLoGz;bb;rn5M|ld!sk6YWx*@ep?l2C@cK;TvdQ=^VCfzN z$0SdiIyN?`RW#x$E&V}*^^WvoFr>}WV(3043~vlBvlyO6c6fU|-pK;@uueg2@fDPY z1x|>Ca?40UgZ7G$HbBBy&9}V z;|*#D5G^3&$+>Q(PD&)i@<&Nn3w>1COXF07NM}XoFV7N{WxtzieCZ(m6%Tya_pa6Z z7wCy*8_Cb@@WMrik>|eN%W{pZ*9*f6pl4aJ7y1cg1xqxOj$?i4ds*@7+t3M4(#OqP zT(nECBBMCdyyq9PzKk)%E=Y!_!rN>A!TD!uy0UZ$M*@ZS8HSv-E{PgjsZFpfn_4;5 zV|E!DG5nH4FIff~7^p8}D9-9^U$JhfiR>Fr(D`03Mbi==UGMyHy{#pAw&xHse|G}C zF%lcU^qewK3kXS1tp6)9h<&6gH@p_KZ~Vd57#y;Wx*FK(JiAuK^JrP}xk+`GhTzEL zKZJE&7{{zJH^W77L&odt&dBnPzsR4hE_HZNBD{m7rB83^h5a6{4ko`)^N}1JNb0u; zTuOj2!Ik5~_hOOq<|gB|daq-!6GwBR21uo1*bj^oHr|A#qy};iCebH`s_TjP(m;CSwk z9~RxKbj+J*J`?HDtJx4(i%Gw&EUyHsNxUalO{Zx*m~ zzrWt|317Wb3)94}YY_PeUruqyQ^oB;{&Vn>sNZlV-m%oNj(8Of@L6W086@{1A`D8# z@#x;=_-DfQ-_3M9Cb^xjRqFjBtMZK&Rxyx8%O6@tOE6S9-5>&lf<+cv&A}t}c!6gY zEpKi@M~SC-Df^h9L2wvs07n0mWrT%+m%*FRB7}+2mLC=?4(uD6_A!=hdXMu0Se!#9 zV@R~W!Q8f&6-c_so4WOzD<33zBC25-xq2`FmrNA}ZEkE)Jr)Xo4&=WacMI$ZK>Dpe zNgOa?9b6eDHrykr7@zZ#C`;6mv)SY@Z+V7SGL%rbD+_ugO)y)rqr%aO_3I{t?70V` zMA6pEKY$09&0)==l7f357jFJG?yce&%Xn3cT8UEDV3L)UOxMwcZZ|66gC@_5pVzbC zh!9$CfY8Ed5_s#UB$cBBtL^nhrbt8?ndm=qt8Ux&0r=N8XAaI0Wy?8Zsx6HdK;C%% zF!9yeRY2tp zJ%(%{q9{cH-5JjZ1nTN3c{$9I$KdU~gx&W9Z{(MP zLv1SiM&F58$$304)A;rx6kUKKjTvt?ie@yjfc;1xsyh^-&UNRB`LxvklJe5Z0p&-e zo}G|TM?bT3=e%MF3;ceXnEidp_0wXjDh6gHT}5wTw&vLq_`xC^oWcJL?NuZ)L>#?)hN^t7H$_%!H|d06EpIK~u<)yOMb zwXXML$^3Qyk0O;XYJIQQLCl-n7CuwtV-opHFhvo-9#|Aa7`FF$dcO^ctTpRWAnLRq zYsX(xwxv)G^=Y1Q_@1mN8wU#vSwRP$4zGnA2A<;Ck#^fpgDB3r9CqaRpJX6VFMW=E z1awjgSmPEp?d@%Rv}z8=hlaF@!z}WHobfNfUjRzJPzo(uM##(`66_ zO!L4kvlDkN()cASX!UD59-?|Mn#^3h)?SBazLg*`QN2(Z=_IFbkxtG^Q(ArhZUelP z9J)@W`NAO>SIuWKCa~zAWUAh~PIalVLvj54s6i(^C-JMZccyt}bUNI8eUKO#_XvMG zSA+<%Mf94hoAg_)x)N$;t=?aenPjnv%HN2(@bR5ZW;sl5DDn2(?%TkOOd!<~r=~){ z5$zN0Q7REze$QKYRv#-2M+C5A?6u|&_zk|=%&C#^NwkKE15N6TiI{laJ9HG`=b|$ zU7aM!oe=W57J^#KZXh6nb|m{xD_0{EL4%Tw({IVdyjF%JVO|?|O|YXDU71E^Y`>~V z2}lR>vkp+{QIK@KzLc468Cjf2^kmcSv8w@QLj$|DT>vHlJIMO-#p=H@YPEZ;-pM#piIr7gM7tlQ~CB)akSqX%oj$haZGvWjCyp=azhX*%*!;T zuUv97Xb>u3OGPrQrnDgx#HZ0s_ORR{P8-Ure6>onAQr%O(U4?n8og9efT% z=mBc3-yX~lz7G33MHpj+ygI*{f^OMfd^RHVhP4oKN`rbd^Yr3>q+|2@y;qcy9^Gne zVT1<2YeR6%PM2(pJoYkCtuDQ8%tSt!pp|+@V8IaTD8=%0bZBS z+EV!Wq)+PGObFz&LsRpN&dmzuFmRc)@gN9$1JWhy+wqWBtCOMeZLNarvjO)BgA*vP zLbW4r-<3=hq6krB$ohknTh@8>9j%Br<|b85PiqqnczWx_5Rg$A08_Z*970cobkvEs z4Q{r0z6f6;OJoqk_*ybi|5yOOO>E~M`N*AhL&IcBS`LPyVZif-;|YFF3H&x^v`unH zjE3b`AxdARKS;Bul-^cKuLQN}iS&QlpYO#9`e}3%eJ?(?8kV4`r{2LEmS%c2@+jtg zG4qV11dhHEao@*ug61T&KJk}4xD-L!&-u5A`19B z6+j-nEI_Cyd}Ng#8VGt2P%xAqwikvxUa$8;E`cTC?-46uAllJ90Smk!23%w;V$G|A z;)yz5C}`8(k^M0*ui~C9Kd=Alld9+9<3C-LXV=tq8Kz0spqne--8HvoD0_c@W9Jue z#yd(IWag@+!cW_>zO9D!>_H2~ektVCVvtg6zWBcWUFDmGoRT@SQW9@(jd1&EAz|f_ zl5O9DBg$pJ$MI_4saaUA_EYp%Q!I-$hjg|<{36}|64exry6P!EL4Q_+ z)j4jexQ#F+wCzNvzLf?JWVL1HW+o=Wsl4R@6UOnjy6(N#CURE0fa7+llNm}FjyT|# z@fX{oB*=Ed_|N@Rq_vmvo;?!ba3LNCK{tSr^NYX`Nru4FstOM7uQa}E=!IaDEKWJ| z_1)RDS}xh=1GmG&*mjQE3LYNM_SKagf=Tq!8tPweMNZcAOK{c7s?KpFs^lhCdW7Hx zmyo<_5m{M!s;`ssoJ1ayBo}Ik-%!pI$wehA=%o1Py-}*rq0RaxJ4-nqeH&%NwuxH( ztVbN87MVj>ZncA$N4d`?Jy^7T#TS3W*u?m=*JCzDEDf2k_5OcpllMS-eehPbuCV;e zm)!WKJu3e7rpH`ZJF569n(7L=_e#^65=-EM6G(+N_E+Nf^ABE+ZA!O#vjUl=M;S2F zlViHiK~BE7Hu}H$7BYn}jgq^F-dybMWJE9EqdC6qQLM}mCZpVeK0}tlpkE_767umL zpriW3pWI#bt%EjZE%#Yma9?T4X=B}VC&ys=1Sa#seeGynhbJ0lT0ip}aC{yLI6S`v zEujNiJ|YWdO`KOR1UR|du{-VRd0Dv`ojJ2;CBZ}u0!UVo5*fA)jY8Kl7LQPVHVu^* z3z>we^wXrJCX_pt0x4#K#E3PDR6c&7H|r&f&~KmN0@H-nCecJK+9;fXdqpfaNtTk5 z-)&FlUSvXi+>=bCD~PU_AAIaR{2-B0>Ou5FV&%{U9V$D^C#xL)sIZrx=6$ZLGT@jH zph)HCWK>mslbQQ2cHzg9bvun00h`#&uS=giWo7neP*bvq+SMED`&4=PA}>(5Yls#v zaMK>__VWVFZ%?(E%oN|0=uIn?A6pAT%?_@bgga!nGDDrN^B`Y*TH%M-ye_@PmLj0x z`&h*ULIW4&ZA`-KP)RaDOppOo-3-$Di2oG67W4<4EJ@-z_k)ET01amVAg1e`*eN1w zti4n2f4R&aJ^7lfIDaNX<4j#CfFfik2@%teags=>BkBB%&0eF#wJ|lF9I}%}k&+=y z@)duLKeV4iZQ;ID&W%j(C(pD@kKwmve_Sa_GkZ~ynJZ52Ot~$cMwpVH7WMXoDp8&3 zHHuZa@Uh6NDvh@V1#kLP1yTih9_bSd2I43E6Aw)$j61$*M6qy7VLalj_%ih61;+jt z_58eE~imAyRM7ue52B6y9IMQZs`e>FMz*_r*xlN*%HEvlEy4vOSh& zC9HVVwmMh!Ayq|_KI+2)TA50riy!I;>hmXbTYSynd3x68u9ak%3tV(et-K)v*=mZWw|dgpE(P5`i1@DYLzyPk>wL1~ z20asaG1epJFB+P1!8QyHY!rTSJ}v|aYXUl%>CAwpFT<*eHiOt2DvZ%h!(b{ZJ8N?X zhKa_;l!BL$s?J#|+K*JHEmZrN#oAoEBmg7rv4TZxWdT9U_v~O9piCID$YR!Vj`Z^k zESO}>2h(1TUR{U-e#~IiURf?Kft4W$KWI>Bn5pSCIYw>BU2514C7-mjMutvC&eYR7 z`zMc?{TV1$*S3QuQ?uVCg4KA#aiygLe&~=FsHQdYNk`RaYAW;OrDZX~-f-IPz!laV zwdE`g#Rs2|C=Sk`{X#)+pDVLUIZ`}--kADUoFORaL`zRSx!>ZSXs@c~QcQM2)i(+9 zWuVZf?0?qGX<{Om{!IZNZX=*4MhGr-;5QenPqQ3w| zfMSS2W=A=Oi3a7z{EpaqdU`1|GKzR+d;Z9+z>tOd_(5`%J7DcxVv_rpKhxH3`xzto z@^;!;V8~Iu6|#UqnrXKyx%)UAunJ~chRAdvL@9u!Q7g4q=kOl}3667MJG(^WIVf3V zz*$mCnV}S`)JQEHlTC{Os*10w@$`ZDv?t(D6>2bDLkA}SJP0^dse#jYVGMi!RJZV zpHEG1bnHsm33_*tnS9nCX$`Y8GU84W`Bma=YsCSzgDhfE1C39LNE#l~7SQoZU*Jkg z3i;Y(OfPt5H6>XLYknXmGsv@S9uvgrf1-IH7QaQN~wO14DGRol^5MvI!-S&^z@6)M`v zh<^N&VJY+D<)`FmDrA3*cOPLY&5o6|5GyMXAD=Zu^wmFHC4@yNNRX|cIM$|r{8mMi z?yRK0G;v@!-S6;Q3xWc|8gfEw_f)&*W1{GXq(@0j=#xidTLHw7eYT`56_H)$;bjVw ztO}bVBCSks+c-*j&ZV`Ol#HCLnKhw13$}Pv$JaM&eBpa|HnjJx6Qytc{3_ZzJE8xY zHTb(w{Ce;vw+d`mrWx6{)!gGedB-7c#5gyFVeF=!H^w#ZuAI?@z?J@ChO1r&-986HSybJx74Pi`s&Zs}=2s%9B2Hd4IX@I1 zqx=zFIR(i}*4I3QavqiEClVTm4R}gm=bYI3{Jv{$YXPAmvAxTyn*i2qd7!c8ukPi$ zJB;oena^ICkEBfdFjAYfDsh<$E|^9${*h309k&0$19R)tHEcCFN2C`bh#@7I)-Yo3 zC63%tmzj|yyje`V^Qk&9Vy`xhLs8Ac*(5JBKd-FMa^tq7Er0zvdGUFOJDqXUXFSoQ z!?r{|XZqL{UyH)LYw$749QL^i9=Ps3h^AARcRfcYsY%fDOh|F>^^(^Dc~ z5x__VC?Sx|Kq-rnjhFOUMd`nSN;T8{$QrJjPduNQd{DATkR*=-RVIavfvEZlhp@X5 zk7Md1k=LZCo1gLRNnUjH1=2DIqqZ7(9~rGxQ+OetaJz8yUwZ}Y!zg}Ak%m09GV<)}JRa-)AjaF{as1e{5t}_v z43|3Y8HamP-I13LDQT}z9}*E*Z3=d82O_RDt#$jf@hSX%)mb?(>w@6NGXgLvnh^MA zx5`X;%%nM#CjVMs&|Hj`rvzWCgd`k7;^ArwoBr=(Q3;nh%nkaULP-Fae@!9)*J3;w z#67>(VrZhTM{iJYP~8-sM`K19aClX%iW1T1Bu)kL_N-MV>6p-4*M#DgXsaS~{s?C> zJi}&iInVRMVuv_J4>`vk*AiOQ`OHj$mrI*rAjPA z*9>6z>lIwrD)Eo7h_W< z6~`tYG=_6wT2jkN^H$+@s3^aBku>+P!ON|HLQtVIUih7@wjgFkHwB}X%&^vHuvR&O z1u%FhO7xFhW|>H8S5bz#0FpP_6v4YG)Y5KUg2hd|F>~%lQL`;WPruvTSM3~e`D6&65*{+fx+coj<2w#AVGUUu=Ld$tmAfjap`_Iocx9-ux7vY0fy%ugBqev97IL-Ji#=ElbE4!pg+KNuLi*4E$bk?Ez&#OLz;W z)Jtl2SaFM;ScW;|+#b}|zerb(abmWOJnMRw7jSErpZ0(KS;uG%!*|fkBO?w8E-MLY zJU7Ud`5nF;CM&vt+ZuYpG7TDddKV}Stn%+GDG6Mee!Q|28(E9*kweH9O#>{TaR|in zBV}7nY@M&0^i(b{W6;Wbv#K8*|C6M%8iQC#0+V~+PdawWw(P&DF7^7Z$gy*~ypPc8 zIy$pl$e?fA0Oc!gjXXw+UL;By9Ldo*(1YGTaJj*Nr}~ocWZmHn7X`<(48K_RJ+5yX zO%fjq$P|`|QpBP3%9XZ5QnqfR}XjxLg`?8Vl*vH{wu zGjolvn#joT8}GT}aizhNp-DnhcwyPYl37i7Mfz0dpf@sV$-tGhKY>7?Jis zlITH9J=lW22RJ3g(RS`e)PCjvl+QToCEFvN(6Xb6ar4mGC+D%flZAh>gI)sd4PIvB>zB56jm$ z_{Th+aD<)f?@jis8CY*M=@(^!x&3~#fi-Z?HGwnqhO3wZ8?B9_$?+AKq+@i6lMly~ zZQZFs-;y##+#js2-X%UGm74F2_8zQ*=>D!zGPoi+(iX!{*rP9;__)(KwOUj~$tSt- z=%YNa-BCO1pUi#->2|idBauo7O8rSD=s$IM;pPPw1`rJ3ag55uN^2u_%Aa}NeWE!$ zJUVz35ThWZc_f;x&@`E#>t z-K^C?2OwTtwvUl<8&IC>_-^L?oGK%cGT)n>q4LFCtDBoZENW^$vOSzpoMe_PM3z5AIG>Ji7&n*zzITlLB&ajeHE=R5K4+dLsF9Dn@Bqi$U)S z-Aib4F2AriKIekAnfs~&cV-+0Nac5gk=1N>(0X=V@>MN8aG`q{uV5a(P2_dHAHQQz zhpQ1UuHmIa2Ml^2!Lr%;wlH!vp+YD3V-M#E$ng&4cOtD6Wtq_Et)GQk_DdusJQ*_( z{waE>G+N&*$%3A#KZr(KHffS*3c>1qRCrZCsVjSCnN;EUXR!a>Jj$x&JHlj z6eO}V{c}PpBGdZsl_Ju90ZXBa+WMQMfV+qH0W5e0G zyl!U(@G_^IejFDQNhz#zytbqqP{eAnc$id#i?SHv-~Q3nYON`?m!0=f#JEtn+4fZ( zf#>q)2dqlD5Sjb^QzJRN5?1}ztLG955lIO$7LmT}3sH0}OyrgL%!_HX{yq_sFFln0 zoRD? zLl+b1>zY3SnRBr69oR9&856aLivtKTfyc}F8wK$}xd90=IrT-MST2EX@{^-#>9uBY zL$D5pGr>%&sxVwEaQsneR%_Ei#r6%7l7pMN^{@dO-s*wn$Aw(|5Osz>CJDGtXbyhu z->1ih;A*uPkrBx1eGBY!0O4X|xyC=!x;wzhAOtjG$JLv_v&}KhPp_GGxO# zM;@x;#0wgHmWk<5HFU{}%e%~GsO|4zmY}ZnC|V>NR9DM2kkv_vPBu;Ai>(mYB|kNg z^^|xJapMqk)_ls4TH>V_gBiex=}}2WSn_UqEg|i4rR*$c<@3)Tpst)Ve(&KghQtGZ zoP2Nxrf@ACM%dE?9%;air;v?|MaTZBx_4iU^0?C~4(Qj4U{~^oG~PZbR}s0-r>409 z=nZhkLbMiysrL(@RWe|k+g-;c3Cyh=Rn+1UgZLREWhrG&60Efk*me~z9uwQLIbA#G zv*GKbZ|w8rL#XXgHq6F2E~GkMu-h!Xe+xxJP99njN|1Ytku`R#c(mVZ38TpBcS++@ z3y{4=+?6<^fZp|Lg>j(V4-?|NQdbPp4S7VYqosSDZhX)V@)@6N9yMJaz{3{{RBJE$ zy^@xm+egUkzYzcJG9Y5I=axGeaQr%;lI%FQmkpbk#LtBhyqh=Vjmio{g>BGboBAK_ zB=TM59L~kt@||7=bKJOO3a_ucwuS2aUU-;vVgH157djxIuG{Pip*8IYAL6N+Z>0u6 zi9IC7IFYZXWss{PHZVoP5#A zE25Zn;?AZeV~(kitls`lO}8y2fOJt9CBXixju9{6*!mWoKyH>!Q#NST;jnQK+nuag<2?Nwd>uO z{8k-erx8KJ2StD5X#_COO-~9ij)V*#QN!MqIzOwF8m9<4JVmPJk5c`H@mtGksNIEy zYVxHqy`yU)+rLG!y?oT9L}+RHnNTSBX?DIAVkg=&viW<0(pg&OX+-&IRVt$1I)u2X z%tEw#jKe%^ai62IB1&W(Apb5*no?4W(v2+~ErnG7yP~_FYLCnOS5xecM}}-GoM+J{ zf22zGi}kMQ$WOg!KnCGMHxl@nCGO~f6qEm{>BkX!C;yHWqEClzeQmTM`!2MhN?;d{ z{?@KW^!5C_)gSlQ&DU7N1>%p&^UswzsF1~D)L7`AXjqR+^W$}2!rntSEW~B zHD$2AP?JP{Z(TSR`lucEqmVtHN#%;$_~VI>gCo#mFBeZ7p8bfYY7NJ!KktZ!!M^m@ z!BUnNle9#@Mk3E&f!46I2c|ieJ(0dwtG^S({lvdnhlD(R-dHZ{9l*p-v;1X98|kj? z9=GJuPf2+f`F&b4ilBqE<9AlVF;6=!`*$(NyvqnVj`_MyOko(7Lk=AY1lOY+pp}Mu z+f7g`Gx*6Q19iO>&=HBrbV@lHZ87%0oxYmbpmm9w%i)Yw3vD1#=DwM&F?4Wb9Cv~w&vq% zuW@IDa6cv~?Rf139%U2zbFoFm3^LL!Y{pgE)ffQVa!BwWgP!FXyrJLP-_>^Zn)f43 z^szDq;vNr7ItUehw&y(=6ptB^SgFIcdOqD}ABvHt%^2V2>CyK)1^-?o(0oShM#6@_V@P&D#2y!|FJqvhUOJ?eD|AG;}3c32`-dy0Jrq_k5vO* zhD-quiQ`*|yxObk+86P#rMzf=ksk^%yXcfmR4dQy$Pq$yc^E^9{k`HAw@-4$fAJ$6 zr%PP@jkw@canlZwW0$o?jY2t7PNZU}=Iuh=_eI=Jax+_UC8k&%2<*}Z400Ix`*!Xb z%0E3DO>z}A^6LF>QtI(X0w83y>2vO0ZBtHVtq^W4QEuFsFgoLC2V+gmncdGtllF0% zMuar6$g!;k<8im|eQP`rQ_t7mS4!%hp#%(jNPw^|FV8D|gGEL7kH4R{VDh4@0VyC6D{UNkQ#&t=vMQ7nzja!`=k^=BKo=nCuL- z=at}r;#?&>O}M*=NT0PX3t&|YE!d5hVF6JYXT}yOsR5Sfs+`?K%T+xIx#lOhW*R{K zNK1}dELKXP+4XufAOtLzHJ{Ya?0%|sy~e+4(k^y+#mNqY322J}+XvN{Y3GR56yS!z zG;~dI=Btz2&|af6p3v{&t)G_U9G2}scZImJe;k_PO88t{Z!du(Uh`94wDhrcbYAzK zOphwj{+}&QZhs|9`%5HQUmkFrx@G~V8s?bb;Dp4*<^_mWKU28&Ks9fjWm=2OS_w_9 zBEmX~s;cD#*W=QX>r)0>8G~c4g)yMci&x?JB$df5rLsM)@*(PErZ1~!XpSWMrE7;0 zKOI%a$4b@FzT~6NUhy>}JDD9o|4Uq(sN6O&$9uS7kq^~^&Nv(>Hp&urej*8(FX7uw z_cGmX>kM#uCv+&TQ7mA6dU>cjo`{PO-Xk?$(Vf-Vhg#JxC%2c;weEu&eys%R<9a{B z32#xYA{q9pZs7X6W)7#2qP6*#NO9e9zBl&@+f{upoxNYua^!vN<9vzHEuTIoLB!e= zt5sm{r)t?A+c?YesAW&cq;t$-4P>M&`sMJ|AXnL3|G4f$#l4KjaqG9#)t`W=g%1tW z46XQG$WFxSJEYi}Z-5e^9y#ahYXQ(MBwvL3Av{bgN4LLVZ5R_6v2}w{D=*0e4Gqmz zlwLw2!8x%npcNPxjfAIsoev2+MKV<30=2Ub9ih}C%%q@8w$uQg4%PTVo(|cM&3nDu z{>Fc2;9s>r{2ll?`Qf6Mj}F^ulq@Kz?!N=NMdJbr|jP@S| ziL4H~maV?0HnP5G*sWW=v~P8owJ~p5rRyyoIQIVYwz5C`wrg*$GJ>3NYh;jHWIXIW zcd!4nxu&-%n{mJ&xds0#?o3P57@0*MR={x98#7Pys10=*s4aAJtoP3}&p!XXUd$C= zn(i=d-uWQ#X2)T{Yf;Z!d8f_pyCkUFfgE5dL<6N6L5_%2_Xw%eSf5row|ZRYp>ICn z+)t=;`|^j(5ts*Fxf{3IJ*u$~ral`PL1=OTl~6)yb#}}aAvZp$!nr(9&IM|&nn7Zb z@tcg1fupB{|BHmyvt4UauOGIaW)Iw-_L0oj23Nohi?K|$gfAUckI~72?}Gx2wL9?eAwQ_G&}vS zZ1`*$-LXA)d nx^#QX`?plK-W_|L7ICC~`&H)RtnxPOjPN3EuH3We(D;v64)I|S zkqwCmaMf90xBpNJ_~~nbF4%xg%BbmW#HiJ)TODF#d%NU$qO%#s8GA1vEG~M7}l>7pkB` z`8bggUiF8%g3{5#gm$18=wf1!ux5c?{JdwIB@t8VT%rg_jO8Xi!0}GM2Z@JG^l1X9skxv>j;7-4g@dxrJZ;JVCi8@85BMtA1jq zqMDgcWboIXu3dva=|_lHE#mW!xeD|+|0rr)gR+54YL_yNWCgp`|oMdxAy|Z zBRz^u$Y8}^iETKY)KrBGBj6aUXvRPM)3arz5z*0m+{~RTqn_A%bJ*j7ik+7Fkv1TC z+OrD`A3E-?51b8L4o&`POtu{Ur-H2F+*BF@YutJi;dtNX7R%+8zR?Li3M5IZ^-Mk= zkPPcSTT87YWr}EGk}Y6_oVFlroMJK*RdbX;{KJ*F$AK*t>?o;oCBz(Gzh94wzWbL?l>Frrz6!%@*3Bc~q+kr9({F22FHOKU%*l{Rx+XPL zJrZ;2{-md$j)$GSBl~1rXM+J7+bU|k?z|F(M!pKWMUzLtAbUqPbcEZ4HI_ErtJwZOQIRTi!4<4^Yr#eOh(d&8)D1G z3%1sZrJufvizN8LY@Rk#C>TEI1dfz{8z2=7aDa$4!~8O zyteEN{sX>l=^;(xP!*98)cOm)jwZJ&v~G4p_gz}|+H1s)<#;3_wPW!<`=LXbMbYEN zmQ7KLl7Ld<6r0*kkFiD%SVsxuXM+_I2?N>;yp1~TYRLg(%zl!fy3md!Ux-#l;+8QlV;-di-rH+RR5xb!F3tM?OB zTF^MhIObbUo(IY?Mg&ASeuu?MT5d;mHzI+gpZ8B!b^%T8I5i%|CE`0Y9=1f1AeoTx^1GRH*w*Eap%)*qD`|n80gE&NEbbfDg zT^nV`ybxdJ%R|#9r$FNszA0HoJ-IEzqN&XnI+f8}P6{2>Kw)iqgJh)`H)6bbKRz(S zAvP(C+YBC4DRkZdYGq7J${0xZ2k)V6{M;~JyFtXr)}3@fB?XBYWuG(+=B;V4Fjw(X zG~awnpUdaTkZBeL=RQLCp@bbc=M2rCF+x%+MF5e0(4DbbJ`Yvt;Q=Uk=WOQ%#1(nW z!~mY<=r%Hmt35OukF@HMcW$M&&ZGWmMVYJ1Zp!e^X(|X+D5z(~jfY!3<35L9E|7qm zM!}sg-jr?b)vi&8>q5rY`Vl_3a_RwjX%St>jai_nnYSxWYhk!o1gG+H;sjDjTZ}Dz z$aO>jztQJ1aTc7Wv&lRZ+1T2AP|C>r$<~Rg22st=Yw(F61`(jf^$m+hV2W4ETSkli zzEAaXpQLFbpywcN@x{gD2;l~;^%N)SgYSMgp()4R9LGZEZ(M9*&jh#&`k8l1jjJ%1 zb;EwiwGQO{`v;(O?LC8X?;u|jx@~F0PxMKCnqt|E2GY62AI~_@6|*YVxZhXi;v71n zN1cm9=B-FJCVdttNeX%z4PIS9zWaa=ky!u&Vf%$aly}+;ODwRrFl6= zA7X!%*`Fixl4&y1p{!h;y zzFuCFI%w0*Tc6(XJA!EeUw%Ak%%#FYY#cjJS23tJ$l1GfimQgO>O`x}eM;AY3@yU^tD(2JNKyq&Fe{c%{6kuIQO$ZL zOn5s_>6|lcnC+9mN1$`jwe#l*e*g`9B-m-nvsmm0fxbMJlt5<$!Q?ML-3}%1vQU@O zCZf+^t0|qO55cmaF2$f_j|t|zGo33lDBf8moS9bRkCWp;ND0M=3p)sdQrrf&Nw;%C z0o$C%FPmFO!ZkRwyqj&`pnTBW|3t$dPiK*=F=j3Kn<+5;AFAH-9nSZS`c3rc zy$mygZ$d=xM(>H}z4s`igy>zg5p5(0q7#fx)aZ;75`8dwi#FQmo$dEL``E{^|AG5{ zalN?CYpwNJr(MaJH`8>JoJuxwafDD&k_QcibL=-~=>j*Mqowtr!9$gfM}1@4lleW9 z@x1lBR^HAOQ>og($D0v40Yl5A{gJy$pL?awz$C|P;+3h``Esv7WL)KNbT%>onmfeN z^!7||M%Vbq?aTss^edMiUd7S`X(!J&=mL0o=*}|Xl^3Sx2#3muQSu)l&IzS(a=%HT1P;%kU+Q11!4Mtwuu z*Zq77v@YumZ?$sUQ;hE+xE9gQR1ap;Bx?Ty7>BNlypVUT8hGPPn)c2z{kj^geQu*C z{b0--b@2eWOM5VHUi@G3WN@_Pf795B=%}OwL#mAS-~SPZNL#rw(`GbCXO7#-o5=S} zcta(6`W}%La5^i6qi^=GXsA;4(9SG+tDm$YeiCU2@)h_^V0|cAtIk_A&-jR#??(3} z%$2#qQ4PlQrodq&h0a&G)t^L1BWl3W&9I1g-%N7ly%cSEYfMgJDNs#>xL< z(_NT!rLpZWj`wupEUjC319YSNen)%RMk?k_i%QwRC{{Qg8FncEEi%RBvkgRqhQ^pm z=}t($H~8%NI9vVHDFJWxumczw#IoPeW{ zKJqg=_BcR^k14FLo+x2X-OkE8Y1IX~q$_v$H|mLZ3frb?I-II%(p4Eb`PqP(!D@4V zJ0@~_@=07F69rLqRRvXcNc2g0!cwY|Dep1o)<(|6zb*1J@yI6w<+gR7*7Cfxg$=s4 z>Q;729^$tidGOcFzhLn}WW?xz^jDU(N0Ur7pD)t~(-WhzFoAx3jseTm#Zz+q3F`Q9 zWdL!%X3S4k&wxbhqG1z1p25gzVYRalWs(%*o-oy{^|7YO?3lWMO3D5r7Xh+I~=> zmoPt#Pcgu6z~hLpiz$Casuvw$b`P|>)RsO5bJ-z`L(F+bBad3F=7$znir8-M+^ z>2IT@aQiabN`8SigMLU+cz%(XF#Z(E^?b}j_&n*;2jpSokSR%O14ZR2s3*amGfhsw zrSt&JG904*SA%;FelOiCa{y<|6P=ddC;{`!UZqX6C8AF>Pc`-$le^z}yOr3}p;=Sq zpN!pv>*WwTe%4`t&qi70eP2=$WVisMkmm9^X+tWRlf1oJB&mVb261=Uc<_eQHE2!@ z6iiEvpQ9mP0ttr^@8+eBtY3gUWz4Vy45mCFdk2E##aC-ps!D2}=Mq|x~F zQSPB=i-rue;}Dykr7-mNlo+qHiSLE@9_!_a3*(SJ9`mN;@(`Ev(XrPO=J%dZ2&>A z<28numFsU9J;uybZb*;@t>iz`^ZzlI2$fUp-_lbA0+F0#Ovst5F|>j|_LL?IM8P$| z(fLA$(HS}~yWiOU?7Uc@SyH39loWCXA9u_PSS(VBpJR;k2KGb~c*#{>%0-=6Gj8M? zg`rtt&y;Q1rgluwX<}ol9{i@IGInc0PSLqbY4gKtUnpJ%EQ4aJGl$Ih_QG`Zd2w=! zi$8kl1iOq+6F%iqJ9Fk33TJ9CO;japBGe9K;DP`b?tT0gz4b&hl>*0^1X-<$g5F#q zG)E84FI#X9$cv!rpG7?Bzqyn2btj}Nz4fR&P2ZG(h9%=l(PS+wX<00*c>A7QH;vu) zy4LXK;%xmKB#`>ZX0jAY#f^tn(Ka#8=7i|N6FvecidvA6f&gy2{PV%Muz8kVi03-b z(BaES8zg?k9Inj9%sCtgNCohxL9YRNJk9axjapYHI%3xKSMdENts6=X72AEEvMsPu zAbe71ISL(3i*E96Ai_6qi;k&JXkgzUoiHly>Bo>VlNyX z-*7Ct@IWH|aHwaq%G9J^Y@}Hd9!lN|0usb_ek79@w3KDcao4qeI(B$*-W%>X-IC`e zV%1a)BGH>sGIz!7HX)Q;u_jf|vIpSNawT*dn)>bLKZZl~{!ZeThAiMU?RYA}54*5f z<8n#S>)_G{*CQQfq+{4O^xt6QXdL}^7OKQiIHlVm_Kaz>`q?bo)AHmYbH!8jODK6s zoC|4yuSi*Sgr0J{9&_}sgCd`iH~STn^6$frla#7=#Q(DW|CN^Y;tukQ&otb29Cv#B zAI8IH<$q9m{=3_FherDPuk`guv!H6-`#k?0wFR_m$~-H{@@qpabK4!UlDEjor zO31G{+LmuTEQZgWRhcu5*)|_V3pSBAC_&ygc(^5kjNLB(K5iA5_O1sTpqcbi4!a&v zl#1qah=A2^Bi$q3x|e$&U_FY_yuLWLA+L!OXnG2x5_m(C;sNLPtcA-!xLk=aacd>1 zhJ<&_Il5+fOqJx)0G)y!d{Zf3S^Nd8<;Fy8q`g@GDc+o&)E^7uH#pXqVfB2DmG%;T zQp|#7K@#4g>?h?@Kkw63KFcG?5pE|Yp|@cthGdyzqU`*3Sfl|-(zjz~cux^qqDjQ= z&9%R`Xzknsm18DmL3{cC*3xCPF7%2U`^AlXd`ooI)jzu+o4}L!cC!rPCHn(g_PoN2eFn8mX`G%K*hA` zijW>Hq@GN|C%VLlMa5N}tv>|~1qgjM$sE1tClv>(?z0K$+d%wAdFMHz!kL6%X}a%& z?h`HEW7;|B{|d_{^W@>f@m5^2%4Kv3$X_2|CaW(I3GMm|BLJL5J7V2?#|z(yo9Bg5 z;GCQ>gUI&bo^;P&t;a7AS6@!Ji3IjCwrX|mk#`?QdDMen%=K8Te(95s!*qGl52pWI zuN^p0@t+lGyPtcr3%SE$psEFL&u9C}> z0xRaS;jS)urx-T1)aQ(+8k*F#T50S?Y2;J-JPaZ>m(uEPGSV;E#;WE%2>`tlGbN5F z7&=63ab0)>G>ljBFa>gq*~>VL4F2X8Y04~am%yi-$((yj%!(0TCzgRPBB1eCvPGCp zLL;5^##sMTZsLo<)x9Sba>xSiojF-8t=XE!O^85 z()z2NJFO0nv0%hgf$uwuHFQwpnX^O$i01pNz5W2~4LZVkL**k+In%|B{C*j%W-l7d zSM6OQXYvB@!X_V4^*0U%do!}1_&!NPgZCQjdnRScKLiaH)Mwwq!?h8F^Q&cjqNhVnCq&u{wu?`h8J1V` zqS2pX$PH2gB(R>oI7PC@2vw^5Hep9Ekq&isBr!<*PLf`UBcza4j;_d^d(Jy0gKuMC zRQiyYACPgldhDa+N1|6f)17~=8{)lU)l8ut%~`LV4LlLj1=hqJJ2Dic^i$-*)+Wv( zQm1NkQxtecxhYCGECal0!nt%VIjYAl?3t%Jhxi&0_OUAQ$L4HIpMcbcv6^`X^p^{? zjlS1Pj18jl%FgCd7Dw0DS3Lp zLMs9DKzO#**|Qzrec<(crNn1!S#e(hyL;)*$1A-eWuTC6uCZX@90zo@t8t+T2V3Jn97zjN6~PfD`*c?H-`7_Hvf~OEm()L!;{Wu5Phtpbutuy(Pf1Wk1emG#d z5!stK-sg&UE-Jlpu4E0~DKE9rM6o-MY8~S%=J}~q)PAv$kZwqE$n(IT84*Yaf|g!b zXUO^Y;zq^gu{T%Y*O|zNxbH5=Xtxs29sh-=%}fm_;1Yfz8vBS1kk$~EJyh=lJOj!G zmrNlo|6PAQ7M~hi&}<;LS9o!*xQM}lGru_#n|~thYsk3nshzE`{{p)28#soBliMsg z~`Rc`1NV-d0O&NUn|nL3eEr5lInhZezziAPXFZ`_I>`B_V7hovY_d7KhayZv-qezgbaYzGmZzu1Eh`owrledJrl2|Hujz{l){r_?w})o}kyl8TvQt@R6I{dK$f}0I zL8WZj0cG@M&>NC=BD^yn#T|1(Tgy%o4cjOEFYkrL-ej-45=clQuMVlRt*WEIoNi4R zpB;DYfi$p%K|2Va)xx^haOyxY9ozvBh+%BtDxM{u*#6CTJmKkV{W3y%*(K7_7~6G> zH`-f~IKZflUx572nA3BGnB&YZ;0dn&ys9t8YVh#MT)RqgT?e4K)$)Ts z^w36Acu5G#A9YFvbS7qg|<(@)wX;xp12A(eRA?}%RtB;DEzNLP4;a1c2Besee% zv3MHd;=McW2_D!{Znq-l z>%5GiwogM%G;%F6ajsl#HNR=7Eu1?S1goXi@<)o4k>VypMAD*ho_2ZUFzMqbr(hbl z77y_v{A~7U@J|Q4zPN-Y`gYGWT)d&z!=Rycxz_-aR&o*1u4N-K+pf2G5^-J{0%jtt zltexMP^!Rtf>a{zz3YgvFCO)+8N|ArD$;S3+RT9$NwvdRK-W5L>UurhdoQ9@M0e-; z?(5Qp@jG~1Ul3>&w+CV95C1h_OP(|2qE&-$^!Fc?d}}ufC-jdrM*`0(cXxmCa$DRn z2}Au7Ipp=MZQVEckAPmHgxEC)*7cYn@50#lSp$K{`i&UJeMd*u^?LKis7S<85rf+> zslWsW37cGV0jdMrV}1CxYU`3d_s<%$fxV!!XDa+qQI%1gJSSsE0xR_Pg;G`$jk2%@zPIugfje5-@aA}BGkNN zphNAGW|}+u(EL(b9+9AZp5`7qS!I)`PxYB257q&9bM74*ED0vDt^F#8;lzjJQ_uEO z4lj069FM2-OdiCFnT;aHo1y4!6L2*y9;8*q8TGc`oP;TbuIC<4u^qSuZ8d0r_AQuM zPT{O(#Du7~tagU6IH2vBD=FjOMtesv5QF~SLL89%%$r2QO2BnM8i7|fYPxcwJ6kiW zRbA2;AMakBeXOFAGU6l)?Ev6CmV)f8A}1vp3}SEdwRQYJ`i9v6NbzwoHrdUV*gWba z^B53lcfy&h0m4#?4*XkBT5BbEiU%rN3^V${&=64RXDNM-{%JaHGousyi{x>r!kr3? z!C*SmH3>pUxu?>Wz;Hdi11ZQ*gmsXOXa3jt4>EmH|HfmiFL+#m4WW87I@u1MUUy^t zM>VGPDBzFtfkiyna(JExBNK$k1_7-5jG+^7AMvpgx<{DZuKpR z&=uu2J@x7QI`kEfg(j69!fV2WOoXTz&0o_Y_fq;wWrM^ip!wD2TuSbiR;Q;M>E$3WusCA9dzk z!s>Q{%Ssf+w6c-H37^mD;(Q*6b8R~@2BbQmQyt?2ms(l%jfXPEM%#tIDikuiPJf%N zfkoydIM7ykC-|hsjy58K z7W7RmSpHnTNCcs@@9=xhGd;9$p5y;yDMtUlEQKX+Xjyub`#tf|Zq^ro_qh(+AaaE_gfTP8xP&tK&#Pd+jXxN&mXja>HKTBS0ys;K@ zSVAS)&TV>Y)&~_}6Rk(iqP%4XL@A;+19T!tZ)Un(#{g0wlD<9&#POLt2|dE~Ry%*1 z8xplR4xVN%MRa_VpO3S@2?@GAyI4zmeJ_}#oya@*rf{n(jaj~=_)zT9w+Be%ztH`d zxxkgCy?*2!)?w#F{Qt)8eXK8kYWFDM_>&48P@h~nSUiuIY!+uC$D69!XLP?i?xXJG z?Y+A)Kf>nefRHwRFy@s!H9`_Zo53p=Vx_pH`F%4*WqD^830!9b>AhmHw#G9B)<9 z!9a>`a{??yyrYw=nB@VteV2W0ra^>NCg7z5owu)5_#k9O)`w{Id=a~@%eTGu$9?l^ zYrXB$o%{R{bOrOPrs)MC>?cKQy9si)O}_s4(WxNVmqYDzS%h+*lJaJ8Z;UzJVc_%Q zn=Y({p+u+1w_dIC1Sns^4~(rurkaz`>uAY`R7D;oP?>zf8+K^`hfO*B)uPS%zUO_h+Sm~x=%#4 zYbBjY230j&CJ~Pj3Vd%k$|LRj1*RY zYH}`ipdIGc#B9qQC7IG`vn6u7bDnv0?OeU~r&_u%aMxfxAOEoL+?6qEY+$XRs?^y{ zWHl91{PRa4rUJ74TXwBnkLD;+@K2$5cCwTOpLV3{Fqjx5`j2 zjZ?wDcRthQaGb~1dvYxtYx$2mfHCzcNXHnTccc1$lEo(_iKIlT00Fj9sTmKPscdTL%eg1$!sWRg&gv-;P;LmRgUEoz(-M%_?5G zkU*o-!bkHd5!S)ofU>%_6c}esQ}(%N1It>mP?3<0rWdVsPY1cYWJ=uD<7aX(A_Noy z@*BhZtn16mq*60!dJj!TOT6<8z}+tpNUt7ICXE5rfa7?H|@# zMqY@KCVQ-kzQ7nrsqB}ep^w@z9-uQH|Chf~GWq#Eo@i)geOe#v%9(qhlq@+VB5TW* zaO)M1P4+l=)jqy^n>@DlH(AR>00la4ZF9yr?WN+jJ}l-yXZ=n=+<~0DuEF-3)ze8Dv9riYK9;i(%tBS= zcZ8mgl%rrdh0}DG;!#Yg;p&bAv;40dG^lK{%~h^~UUq-AW#49GhI~U5I*^d`Wo|8o z(Zqo}d=9T(H-{L92}!E+tN6MHSjPfcv&Ph0HUUkB-8f--qL0d=%7*}Y8p*S#Q%#lE zoap5AG3tc;IXD6YIbqXh?4u^6>Cai-ss21X+GC7u@;$!B)OAfI-N1oHnxI;K=U&3& zcBasMrztK^B(7g9nhHS|@I#xu#J(Ts_)kv?9uAr}ytzN%b(IAw_ zBYwVuik}FX@%rhEwj?H#6?L&Zn=(4 zJ5I8tb-c1R6XU=N^Kg>}j%yTAVGcae%Oz!7QL*zf^DE z(0D>u3#4Ih`(%!dR^xSoD}rbuXi8Sd(qP>T$ffwUQ=Nr2^xO3IkX}GMs!kLqu>M`! z5uj2_+q^;Zj0Z1Qg4P*ONzf}4qmwy0X^7!dN6eKryQ8?Zeo53GRr3D^-f^J0Bvwxh zblU0jrH$!9mQ+F7yk2E=90+g@={wfzbEw-^-7!`*R2DIi%Z|a518oMO}h$vyt~sB&Id3{-X7BCPD23&ytUx zpw${KxmvKvD*c}52M|qtFksmPa&Ld`5IsU%U=F)RKNJcK>$>=<^B8?M8`B9Ec6DN# zp6lqpnLhmDYuk`6(*NfDqO&W)t;|zMMB+^D;lwqf#fe=W$!-mE=5L@pOGXt=Xu9&i zG*s>jX zM2_+Ei2l%d8{gCP^ZsRs^(`Q`Yqt3r)kqtqs2fk=A2Mz1zgUkM(`{@q%)TK(Q#vLM z7IqgsQ2VhGTU|Y&Vv9v>^!Up195LU8wGMUn7FlnNpk7Y@(sM-%P$%j5As8V-OWqlt z31-L*y2o9Bko4_Rt$y+HWA0^gW3p1v#SIP#KQ}m+bV1Aw~zd=`iI^+zvQeokYW(@T6GPZF2JK}pH!god28;?}12)dM$ zyh0WFZFjVK_#Eo;I|oo4AAf`+3TQ`7OmxDc42P9+<3@?28E5 zOw_>py1Mwa6t2_Y|8jgOc{;4HXoI^>Vv$y%eRW2DN8;PTLkt}L<)lw@nTMmv8QwBd z%&YuLpNG^Y&I+)nX&&HtS`tl za4%KM7`5K>S!2T_9=t`*_3MsSZ+eE!@j{`!2v99^OsqztIwTligheX=@fw@a#qYS& zMY~r;nH#=6EW(v^NH8ft=$7~OJB91nC*OPN!>ug zMnWR>1D*2Rb+DLQ(xzrOt7#7#~o1Q;!Drb;lx_Wg~JQBIkY05 zTC_PX_^zN%z)C}%&ffA+**7GkFJF6$5C=O(sn(S4Gu=5q?)Z<+k^$#UYecA02>jD81( z?gPp!I+Qrbf2`d!r2oE8MnEz5*TSfuSHUbnP5rlP$y*vkig%7p{(V~WkS$uF85hN& zXYKCG#bl8KX~T@seKduMTz&I))F*g9t?3)}Sev(Og^&g-vcDr^igI$s@oII?F7 z#r%b0Ck3?4YnAAyM{0;fm*tfmif}~?xo;`B+e}*Nr(J}=tB)+1P#Y|49E*-2fLWOs zRUyQtc#!~U>=|omaz>e*1;TwVSKOzpm>GzM`%Uz;{Jg8|nT}hI@(T&oNlY9URMS&M z(z*6A^P&Z_om5{?TLeb(d|DYhJK48Py<_qMD3sCK>WbvwZ_vd?<jeli78fNHjR>`B@+nf|0u9l;q2rk+>R6oKEQOwcT9*+KV!=G=+Yc~6V%Pn*` z5h5@mV;}{q2uWKRs=HY=d0&qC>-|flaIrbHr=*#|*1cK5CZ~FFALIxTjk^NRUQX-| zJ{KBq)zi(YV9YCMiHI_T#S*`72M#w1z!$mU`WfVBuGD9vBEnOGKxrm{>B8>fPswQC zYzTJv0f*#07@1~T>)S->!=0L;#kQBD1#>!go_Kq>^uD%BbtAciWE{Vsk6s-HQ+OLq|O~bo##GXU3R0Im9uO0@)$P_QKZ>9_C z+gWcL`xfXlU~5#9wps8O2sdY2uA*@?9eT$HgeCXwwwv4?clz z_OQQv;fD1m5zaJko7Td<*NGX^W(nPfYW@9ayw&kVfS9cHe13@!B-e-WJ5xyW?$8Rx zP}X%@vHpPnKeG6Na*6Vt`=_;G%JZ9Pn2-MS-Py!@ht$N$hFP@$OHEekd}Y@io==Ot&$%o=FlvNO4`B2Ha9SOX0niKN{vk0YLJR z6MrEvtve-u#S+@MOJslxrVNB&gS8Q*sp2Z=zA*Tg{VDF)pm5PS+<(T5_)voE(0FFe z))r?MJ!9Rs;1y5*H9FgygrHYmk9RM6>WrxOq?*xg$iPk(ugzBxzX$ z*CAK*+9`$K_27-ty*=6T_p>Ies|Mb@1seH!Y|M<%^ZNJfK20t~$4n7(422zUxJgAN z#$80Zt>6k&Q|(`VTM+uP$2&W$F37zbCvVVMI*SqK_qV1S-^>iTf*D(su^DYU3F;L< zwDEdgAXc~lBoEG-ENXYz1ZS;gywb$WDf|TgE>tFund+TtR?Y&bcTDY1L}pOK1BmLkpQWlIvVC+L@RD=BpF2}q!Q&$s(Ce-R^6pWHvTaE?eTIhWm>c;(IYKj$=5f<8 z7s!b83+I>s78UW0d2<54vQqU`W?#5;+!V{NOMkt3kn;OezUX12XE{~fKrL;V$C{}D zk@R5w7(mkn{bu!BA;+Tox7bXHg!FLBVMJyyX#ic-lOiat1>5M`U25IxW-q+@fI*OZ z;3`t5Grr@3dUJVOMD_omA}9X`6?tryU-+)fpF6BcapGoHixZ%JM=>hcZt}JyLHdlA|bHO~1|Y5R1<+ zsY4;VlyzS1e->cUL#08hN`ELXbg_+USxcgtsD9OxkY7#N>LyXhO!AmC=!`o_s3FoPEc_6YP%Xz-3sq5ZJ>!BM@Ku0V^h>;S>d35w4T5j3g!y?6^fUqT@x^ zcR!FKY<4Np75SByo9opp7jFGPg#oK`^u?!YvO>8nMRxO9+s2 z+{HMXnkTH%m0*4cQ1$ume%?obCwoS#RhO8?Z*P=rWp`8tVcBsF=)1ywyw-X#JQWrv zv`CW|fYb&*hcia`m9p~6e&iafD)0F;HmK#$f+g>W{CRSN2EFje5Lr^N2k(NPK8Ppt zjHf;y;&_m#02yEWz2p1JzWo50~ET*m#)c2@8$;vK_R$u_#-jh)T|-8IlLGplP}6*sa0rjqT#t>pWSX zYG-HZ-H&SN1&%o@LiaV)G$iq2Z6CtocP|uB`yWEOBZNhN~E60W8x}+hf$k(Y9wF!?yQy)Niy5LG=u(&;1`W?bqBmdc5LY zKnJ?Xhl5Hqu%<^M6hf;$YMhaFn0ahgr*g@_MU ztMz@374V{we1(6N5z*PGTRHv_DO&)VkyPFxI6K}0tnA+pa#s0`ih&+-boa4aBoguH zJr`dGyOf18oPT^##q9mmUUDYp#igoux1z6t1ifr%uUh}v$ zk7-65}JY?aqFeV15z?La&u2rK^>2Hq7)kB4Ji>fYE9 zyC(JFPcXPMtt|LJ2a+qR}P3l^sVnBN->IJL$3H(LNs9 zW0Vp&Xw(>KrSCehwt#ioZuF@RKPTbsi`S)s7Nn-@QuIMSgv#oFI8v52C)$yp)5&5}L?@S5H|J!iAuU$LOOw%^~`NY%y-}>e*o%LYP zj*(b3^^Cb7-JhzQs9%Caz4zjiaXTlFzd6#+W_WWW=G`nJZw^{4ZpFr#j+3 zXr~11&Hx(LDJw&-MthJZpXX#~@-+uP+GPn4BwLsgH81sT4j5W(C&gi)7A3aG6%Rj` zDdp{b9-%2Wx#OBRzJIrq9!JIwg?{~#sQL3)aS_9jY+|K{cYK&NPyWUkv29ipmylP_ z(h~h~HZhMd$-+-lL2}VUe;553YlLv2dv}e^kB!H;)^#PkGKhF|F**KeJ5Tqsc53?M zAjTzQXGQ1vYtZE0j3SK?tDz4_)`Pq=V_F&kThgqs7pBef)d;?N3{F505Ydz`c$nHWd$zRm$S#a4N%*oNE z1aE=kxtE#y#}C9EdAtU7zV0edsyi_R{bw@xbmkL8M|$UOt>t)(uPWH9b|T)<1m}s} zvHoZOVl~(tSI^m^FUuo%Jg!Ib;x@$S8bt&r@f*v(A05pwTyI=g&=fplht%|X^C|~{ zfpj2Hl&wq~HQ^BRdGuCIT|?HKKhc?beT;~9J7tj%x9VBa_o1Jaqyda)Gw^EiqFe1N z%$uyFqZA|mz#AgZv4^jjn8r{xA46>m_wU*kC*(hQ8KPUKx2@cd_;eWm<^u~lPbO9b z`CP78&E`Z&cFXkngsQsN9+ltvGl^c9b@@RvVes{7w|}Ufl~uoz--)*%7cG$+Q&Crs zLlaT8T+VB6M5Vac>kC?(eaXF!ry99Hd$eH%lQ+}afrZM=D_)b7nwB#Zvw(vBBu}Js zsx{4lu>dw=M3UA)N1BT>fLdZ73LoJf7|NuzRy-7RU&en+_{Qkd?0@Vw#uZt+VwT|V-LU%~l-j<_bMKL+KW zj&q9Oxk2J7ztU{}EC?~>1u<_b5yCb5UMrj|WapyhwAL$SYwkh+P609aXcO}DndkMJ zcv;K7k_Wu=G4uEXtBu^k+j(1%i7Lf|UxgT>A^<+)a(|bnhTKAdKfS8|^~b*V&4+`P zeDxgGp@Cf2@d3{`FF+}-YF+917xIgXD!T?viYYj*!j)+!MmVDYBcK7t2c*pU`Hq}v|WJ{rLTQGlDxlhB|hkDE$^0yZ5H zdjG4&k;%?MBXdWVB~RoVbGbInn_TkgS%(yqqqNTMnpW}~AC;|!^uX;uyfP(;4L}7b zDTT6!5TO6}7sPlbSUJrifWPDF`kk3yw?Dn~o+`iPUp_Fe+n!_4{j4=T2{;J$fxIyB zuVu##({vg87r%f|Nec&j>4~p$f#UYuzZj1EORRps&~-mVNWAKAFdEw;)5`Lcz9#!E zKLRXYoz%BIln}KwvqUTAhLT>FXmn=|!6+I#641^!t3N--eGzhaMJZsg;tqf6smj|E zcA~P{wq!>?8o=~kzYRX%hO@iWpIrAq7Lh1}8~eHFH^-%*-r-W>C*(7k!iWEeH9sqO zJ4=A;Lzwbj_e2A(b00SlL2eT+i@wT4b*bbomOqr~pQT`4^7lq0Skj(6E*7wj#Fg$i z$Y2Kz&_QK348yO{k2bthN`jyBSvlOfB7FQu_v7MT)(Mx*QwDftUf|@fWs1<24TIJF z?Q^4ENn@b4Ak+KZFaGyVep}fR{Qr*i+8~ROrjymOJFgFIyJrdiR^C!iR~Ds*OutHh zXd%spqA{oimdAxo5jEdU-7S~+-vqj|NrK3{-p{bQIZ`%$GtPU}iN7A*zZ$X6FYvL6 z^}I)4%!2+T;LNiRI26~QFuyeOe1qK#kt zBC_H2*4jipt~=^3)KK;wc>57P25hqYA=^*H!_JTVv~8Y^^Nh zANe&piJpr}ea;BRx4mR5AJ+<$TDuaqRlAkbBwA zlDtmR*9-rN_ab~)d;3(q0O(!yjtWsh(~iHsP)9Ac+bqcMbp06qsOayB>t7j9pm7(` z%kQqGAlc*{H}Dn3%aNvb_Lf6cvN-Wc%2rF*5D0~>3?^T`b{`rDF)Id^X&StEY zivTihZPG(<>pxWoCljM6Ghki)+2Qy81drd>TJ!L9<_DrQdg&(vkwKbl?SU6Zhn40q zMYBsN094Ntp}UNgy!e_H4*s2Uw-g}s%Xuf5vybVMB(()qseB3S_%9DSFx#J>&|)^0 zc667|t%Igr)AW-stMKK7va4k>RT=7?QP6nN@1PX4W+z_j;)bKU_$#2#>dw)Y?Oq)t z<}Xs3-W)@Ex+L7ZIw8%msJPLqqxT?#~Snbf1EGe`!f04AeztXU5EvG*FTl-h3zte(&t9Aaq_eV7{@Jfl{vEhyO zXpl58s5`ssuQ^gLoQvq4;~lL#ybBhd>rrps;zvU_c@(m>pCQVR==qMs+YTY}b>pm( zg03MnsWeh&?~TY0#TP?4Nf{R>4;7sYDG!G;!@sY6apc;LYhVc0_Fk0SYqJ-bwmVny zpZ14miV%Mo{abWj@*SlLE4WKJWg65apu z59A5!Kz##q!=LHf3vrfXwq@r4>30IsSNEPlI;IJC zfifzna{#FQCoka)$59_$t{k09e;PFpV|7=F3Qnur(`wVlUALE)GrITxgl_-eVwY@! z+V2H#iLKo#%6qXd783mH>}^es^qB53Y8(u+3FI~2IYu}HA=~&OWVuM zxX~RyqRr8qPhT@;n{N_t2A^+Q*7_C{wlmCK?>h>*D%~=)*Zf=vD|t8i{{WdlX1~O| zyROH1!xy2U;(3&wc?A~Ls9}C&1ddI35A~KU@Oq=@*gPEV zYN5KNFV0AR1d*^F`jwYLaq>{4_07SExHt^GVhB=4Cg7FII_!6PptjPxj;z6R;}jUb zuu9B%5+dW7=OWarI}nIfVUNX$cORdPWT+%mEka^BqlZ`CX4f9&z-Gol|xj2(&L7Z1hoekoYI{&o0X z%fcB$9)`nH4VA@89rQ*-AH5BI;!eOhV@r^5wgM;iUV&X?@UN2Ur>Ic?Qaj%;ETPr z`0mSU9RA{6<7q5`Wzvo$J)sF~djDBJuRp1NfcQU_dsK|?a|MxzyvO}!lF zo-q;w;znZZl^0^@$jfo@h-cyQJdTI^UxJK{E*N*s#URDmxMJ)ijOy20c<7xtG5-U z>gmUbm3Z)>d-3L5s}PGtuw=;+JpTCO_|u>MBvvxK;no}R+8e7dZ^2y3r(UdIzaEc2 zwo>r=3(rDF`J_do78BO1qIKx3TaChVF2%A69W-tWK2g<(A-1*8j>oZMUKH~(naMzn ztzC)%SKNpv8}G#(r(cZel{`$;4}ZXfsM-cgs1omtJq|z=@bvvROX;)GEcaLFV*uWEq9{30GLPR5m&Dv)r+L|ky{0E~WR z1DxvBxQ6z{XB6O}2VTY#wpJ*8+hKfR9Quxb4QevjKWf%t`we4p(Ud>K<%(cU=>-^m z-6~kUewgX`SEclZ;)?zlF?=v`#^vGiQK#aPVb@W4`Q^j#?2a991sd=v8PFk<2|EHh zd}?w4jb>E(DyV(ZlEE6Iy268`=p3B%T|X$Q6u5j}4hll^dkphvI^2ygP#wt&8bx$f zxIT9rF37tPjcuP}zv=^gxV8wV47!?(<4z&wSsnE_tbY&FhM$4-CoFInYQ>LwHiH43 z=Iyv4Ndd*N1?Y3$A8`5w7h&ohtKc-(;>FD45ch~j{P5=S?ST6JIGi-%23U+AVDh;N zOqy7L<&QjsJM|tIZ3j@5bS@N^Ux2tVV=-XhVDud{9LZS)sHJik^al{3a_!dE!1-<= z&b(+YRvB$#nuAz_Tg>OGR&T)l)2Iy_+z-o_&B2D9JD>`EhN$LATzSz1Jf!sF0JYs= zOF8Zv+Z(xSRIu0Ii=k(a!{(|sXgihgypoKwM%|2hX9f0HDbFq#f^+V88T<8CSYLh^ zL#GVD(91_-^iT!PQ(S@jsmwQ3J&!3T4Z#~e5A}a^sIR#VLryvqL#{}`fcXB1PZ)}` z&KrxzUfTkv^OrBc#Ea%=!VORb$#}Q8u~!>J#O&@`U@B6NLuxR)dF#fg8P**;Ulyk@7(G4#mf6#@v z?rk;pMYchA_iPMJ9zbPhCQ7U1>-k0H~rUt4DtKhJ;BVgTuAmz)Av+4aR6liX4 z7T$S&zaMYD`6mAIm%re-=bnShzYS4KGaOI!Lhq4ppx&dz%E4zKZ9Vl1)$ikmu@__R z8@vLs7M7~FaP!3%U_nCw)~Y*^bzUOgrgv%%2LGvO#`}M%pysdzp@~%^Y2F*y8ul19%ccRMGj&1%{)R|lGis=(E0TJmMrsH;Z_nl5=nC^J~?|X*J&bqURyZ-nuyXU|& zU!CuKr_Xtx`=0aOxnOa>Vg3z$1yczL2?>eaM}K|l?qesJ7j)4;<}!mVKJcdMv!_oJ z#GIQZ6pziBE}pTe`Dn-~H1n8nVnWKmMlE_e#XI~98V|;7N?xPU;E5-m5WleTpuBM5 zLNP!W6%~p5{Oemh9>@Io^HE-2F0PL_a1690FruS_gj)-0P>G7HpK$Myr(;Sw6MU<2 z%J55JZ)t!&f0K zVz_KkvBcM9OCkTon16}_uUY`3o${fl0s*tjyBLr+f^bFRIhbH2yVragME(1OX$+=Mev zKVE1l@Gp?b!Y)?5h;t5_fH|rt)IU6kQ>m=RKl2L$DT^`rgu^g*eJYlId=<_(`2(z} zHX)()z_sQc9Cpa__{o$8hjJYrJ^TpF&0K=#j~R=L*R2qHs6^jB4@aKzny?neO9$E1 zKJT*=3VOuS6SgSGRzJUZYXZ(WbS|v+7)-?*pbL_)ZwsQB;%Uiy3>OVQ4X>=-iXx95 zx+POE;+#j3u5u&$8w&r7@1Up2PO)PdRz7e%4tY6M>?>AaTZ{KD8I7C23PGcrhD#J@ zWBt|yHdJQAq02_GuO3$K26(=`1fwtblqM=MnneD9QuU8G`G^VlXdO+0{c1#)Pr|4Z zA3>(Ikc4$D3?|BVqaFp`i1^jIfP})n4W~c2Y-&N?u@MqpcFLRf^FCd?N1G-$6D`fl zsV;0lW${LIH0sgOq(N=f7ODzn`+km!hRzeQbSL4w72s$>Bu(A{vj5-i6 z>3|CBk5HRD(1!G|FTMhYoH7lLSUzlt4B&?kG3e+UkfmOZ+fG*CrKKk54N=%gpkabU z??}PwTlc{gucbog-HNz1j87&UhLe`-ND$B=Y)rwrPhP;R`|rT0!%o7t8#T~5TuAs0 zD7EGwd*gdJn1s@lOfw85$hbmwnDkqbaDK<41Q!C{8k?}-8memykLMG7Liq=gpw0lh$AOG!3N9_X9VEI#Q8F3>zc>cZtXPP(=ARLWQ~d2_ z1T{vnPbP22V5UCL7p8d7*yA^?LJ`&Ts6mVS?zjloTssw6CN@Z9LYY4wnVYZ17{#C9 z3>G2XwjSXS^`dg1xj2&K{C(!s2 zcKr7C1y%YW!d461P8xfhY7|)vh?>n}40Z-hh?#QXHQ1pqGvch!jTqK-78F&4ugBqz zpRegR%)anODPDO|)R?oW|4+l651xkeu38AAw-EkF4m{R4Hmtk@XC8AMHd}4bglT*> zN8wDHi8Bto4o|O06I!5bVb!DFh!U?Aubrj9#h=G z{eDC;*5Rp1N8zEnUqV{20Od4BZ3$`7zHBN6jlBh{?NPk@=fOC4;SaF-qR98I$J!Ss zV)&oZpiG;C8wcKu_YDq&b5|jij(rfmx#k}N$WSy zeh*v$8}$ojBrG%sq_NNMr+HEC8oYkf=~#B%5maN8*#4 zFM?<5YM5x=7YI6`X9GhtrtoSEhbaqD8gmk=R9rT8B%U*t!jqQ*bwGkiyb>cW{Z#C2TH(w@R?0Gb`0P~t`Ah}Qot%km{Zc%4+#z^irAzE{S`yfZn}#2W zr?;ettrwgDC$^=zs2yy^*4g_C`5_kLeHyJejM~VsVZ*R(+cq>eH)F(z5wHgB`1vL3 zCoXzbl-Ino55bK~DgPbcV$t}0@Zg$qYELHAxtHVCamV7xEi^9YeuOJVABkURevsvI zz)bDSW>djM?SU-^$2=~PAN`fd?}6VJruMxKxzu-^@#u$G9t1w$T8s}jRp3>v55J@p z;)PW)Jd@$T!nGNA_UB@JVky8?)0aTM2dr4LrS+(vNlV_xm*lxX0q&arCYET*@o`=i z#WR9WQsM&duMgtQU)*?Wl}FtFGP4*rJop*1Z3$si#pc|E2#sHU3+0{1PjUwDwfk$~ zR6;^RLSpyOf4{xE_+4ZkTaRPy8@8y*6T~E8#hQ8D?JaP--557+94aa*P*PHYhaY}e z5OsY1>8GEfw6qk3g@yR`+i%5rK|uk&{`zb2oColOhKv+ODa@IfV(&M58HHb9!G(hl z#23XR1Sp@xd1D{KS`t7?o15TXKMkiI_c)fDx1uI{5e8kj9E}|fs7fQ@P=6avKJ5;; z8vsj81GH8klD7&mlwjEtqcQS1GwR~`V6(UBKaRm^$;uhyzI84g%GhVXB#N4`He!??PJ&wEYz7uw*Lx9iu z9zRPiY2$bEvNnr%nJDCCyiDp9>psHSW5(lUr60xi#aR606L?=)iAwv=xbw&{n43lu zk)?}p@zGQ9`nu%^yVQ95$%}E(6@NiGTY&U!z?z4~;-JfK!i3`|V~Z&OUp$1I?`Ghn z!;i(gAAJOkK@T$t6dN|Kfm)S~qWqAEmsOXAi1|~TaPZ-HV*WEoQ)k0fl!N6fSL3ax zS3;+H23H()B3A425v0lb8?%qc@M9+C+!;QC*jSlF=QFu#RJD4gL|L*6l!fAA|y;J zvwop+(Iap1txz2IC)l+#akIH-5@;oXc{7$y9fNBh+YBA0sUWO`-B&^aT&6Hez{{lj z%ah*)njD%;dHCp~xAFRGFXFjp7h>c34bZAJSoq{3y#4l@c zOLHE!e5XYb)nR_9xE4}hoc@@0)I3UuibPO&cFFSWNS<)Dsdq7>+i87 zR|8$vOStm5i?Jm$0A*-1Y-t~2{6R-!>3S;vazEagHy#Hacn{WFJn+Y|QRwiAKEz6W z2k&pyZ<+lLJTdzrVO*s+p+;q?3fn4_2vMI>oX>)II>Np*6eY3|Bq6P;JWu#xzaDD_ zo}BZrAoJX|Ow^f*sT~^-GrW(>h8~XBQmrKH|A4oin~g72RdA_SV9r^GV*0mR5MKH^ zMjU?%-u-Yf;$|yy177G-H(;Y-HP$_J5-xgR9kRS@;mqBLD~2m@#hV*Yx@jGj8dssH zs0xYfPch@-n{fN*YhnB8ZtQ>7-Eb;-FSSfOe~AL4AN-mG$pAJ^I}sD+t)zNG?UBaH zjJI#VK_}dZ^&3`09jHXmyaHeU^a~6&o3LiioA$d5S%S<9xUFIz)&BCVFM@1bhU$>Z zOXG#Z0H0ZpD1kL-eN^}CG~T#q9N$#*9S&%_2#WgSaeUz|_{9D`K39E+jrL!lk7Oeh zvr`EQC`A!xK<%g@*0?9mS*E6)g5nG=qH6}CKH zLL5Z)%Ej;|wt@|Q&Aj<=T>R`xc(#6mtB$?^pJ+ExoFfS2reW?GM`F^dwJ@c;j7tuC z6hB(?VANY+{rO^yIs30r>3@M+8^@2&kH(c#w!onK9`g@B60_H(QhmtAvQMVt#9=4k z73B)V(--5y!!N*x8?&L-Wx|uQ0)Ia5bj+H!0O=MJ5(QCg`JM!N8mp~Tmb~{LlX={S z`5jFBnuXD({^~?u@H~X;hto@KJz#*|XNSY(6qdFvK|Nwd2fi=-03$ok!+`FI7*==< zehhquH&#D~w9?J}hS?WJQ;gc;=P1$UVDha;;l`_;LoSUAS}Iemn(DPX8>$U6aom0v zU|psSmV6u1HhzzJ(@ww{CoaG`TUeBHB<2)EY{+87b7v@U?ihyLk6`4uTd`T|#@cr-!ineI2ctzR z2+#*E9E5YGrNU)?689f|172Le8dV`5-ko*^Mjd@4HaSA@e)Av>KJ7`Q(mQND+2VD< zXZ-gyDm{K)?y5$xH0+c6OZ1ZGu?@t%N1TS2 z(^9FwcTk^h!M1GbL$>LW@lvk=4F1vX&_fSJvDkCdf|p-@S!n0I^2#g7)1=`3i%!6w zX1$FB&6DptZC^Z-wGAfS7kJ^6QMh)A2I(}1D9>4fyT=@XMY%eJoojK`h=cKqlE!B? z6h(8=1kKUdSPuWF;x<#?r~CIcDjfztqHF{#RE#?oe2e>^`vuqE{RVEC_C3Zw@-;qL znTyxfM=;^xrMTnqwYc)m3|u{B1s;7ohsN3e`{nh#QY7HwEm5fLP=BJ*Tk*)_ui(C? zKE|bwyoNJo{EV|_ufjQVR^!Z>D{=bN@gST?B!tEuZ)nSo&zbCF#~L+!&I2_+A3Neu*uxxd8!S2=3cmK+G&#gFpj_MGic4f0JUAvZ(V?~M@_^te_e$x z`c?r64>r>_*lN?^eC`~Keo+gwL;Qjp+jI@apZYvvjh(O>v+?@%2SIVgD~PrNYwte^ z=RNX-*o3}<0&<%ukLpS>|FQ${a#lW!N;cBbLX!k0>i%ZrB5CwO7{Tan124Jl=xl+_ z+G`Xe;CG3=#>$Igg6v|ljy1YiGmnWkCh!VkUZK^-)*zW2iUqwQzrXlmF|>M}0H5c-a7J`7u11-{PEOPQs__a#0xD0#jxVG=X{)IF{hXID;mig+UY-sIlSm zg&03^0uCK}h`^*r9zb4h1`6UNxKc%93#AEH3bM9*h?}mx90!j)3PX8g_;b(3Hy_%e zG5&}bX3oHoCr!ZR=bwh@_l?Jir#ytsn^efnz7Hp#G7p;#DQI?C@X6F0arT0D;VQDA zTC2uWSB%H3rCY@^Jkw7kI9+}OO(YdKWz>s9_r<`>=R&Gp#jwa9^cMeVHX=2S*6a!Ag6TdA?@jhQhZH6d2 z&VLq?S!;$h^KQQ38f>pxhL*amRQy&nRw>a`oeQ+-(6}uNZFL&7HKtHi*^2sYKcb~^ z1)3UGp}2GN1nD-0KoMC<61 zx>1s#$$CF|@_XQ*`WhmEhTBCv;ui*SUVhPQtzNSMj= zrJ&lW#NtIy;h2jr!Qtl~g=^QqZu3De*|Y4GG+)4 zIdm}2op>=mT9*d9eksm4>LjR4er!>%L)^9nAHMJmP8dHP6V5pm4_rGEryTzPR%WT; zjbtNYbs$7_*x}L&0ieG!`#pH!smJl+)AKR?k=rqK(v5h0?!A~l>pm=){V--vxle%4 zADelvcsA{kn}pw&o>?H?wK`Q|>0FJi5SpM4hOKYn=3~#s%PW;Ab!NnSX`4^mg@~JrWxP7qCAqU~ETNa9C)3LP+G2x1PF#d|8aPzs>;>NKD z;DPT_p%M@A2l3*UHk>KMgs~HVd@Xnu<0^| zFv)#0YwPuwXMN#xYK8S}9{Bb>;KFUKUjSDnpFbVIaxbj}Du>flV1rZExM!q9~wLd(GBZlsWAyk)# z9WWG%eMaEi>)(V?Q-!qkf1X#kW$VOJc-@hLRpMMOlJmVtVeb)?}wEs1DedP)?2Df1DBj@9=Q%}crfBqA)Q-4AF=5KK0 z^_OA)A)|5l*rRdv6%(P;=L!qJE}Gc!{K`*bUBGD;WFBjR_E#tRA}6GzeAQAO7+|Ei zgu~;KkuoOhI9nfD%3cga7BOHin~7$Ma;JzsXyO` z6NjFP0g8dxXXH324p89FS1*7^l>_a@r$qmE(7}gbxbRLImQ;q|%^G-jaGm5r>;>u~zn zXJhE$7hnL@hqF$*0B^kcwb0J8<*dVVGcU*fgNNau{RiXT>+ZpNniN+AwRrKNQ!sY? z?YQRpvoQJU3vk5omm$SuNA`zzV&cUMVDQ>d;4?vOQlo~(o&NId_rUA5!mgva9`(6i z2c0`@)Hj%*|M?TVcHOCX`>JE`>Xk>}`HK$5dpDebH?AKK+p73;8t07y>rvX_}StYoB?n>mi(&3Ki z;V4ld+n6HupX@KpKN3Oe6U_Q7G4`;m5e)d?@<*Yx24MzkV z>6mxxWZZh=09NY~_{(Jtq5@p!@F2Pw?ZC zukiFUPr_i*3-CGL<7Z6zF^R-P2JgeiOLsZUB&o;CS53L;D2SIqYugN8Fb1d52fy`8 zY;*gNU6hYfl@W2{a=4kivXh``D1((IizaIpY+4g4%QwK2>42%7QfxILohD5o%SPnu zcz-^Nuw?9V(`3=-q`Kk~OUO8FOh&qGX()|*5O&jKz@`yPsjU_RGQn;KXcsgCss@I8Mi39X}yFEnjXCOer zWU(N#K|ivLBs}nvED~m&N~PF9J0AB!sdk~Ds1P3V8;?-qpg3Ce z8fdlILICcs0rdqhH7TU@B{x^*Nscxz1BI~=veUMpcH45aH>RSgIvcIEDzw#Sqop+RWS+`bM?bt}=`p+#eL42K+W1PM)};PVuqAdoMFAeWVY)y@-p)_E-?^x5n} zYt#_$q6zXQIAeKeG_&SPD)N0U*nCQuV;y2bR!+h}Akqj&Q7#HCH1Rd&BiE9KggqN- zuOC(;#hWI^rTR@2eiX$dWaZilVM>s&>|KEZWr8Mxex#AW9uC`4Y|5p$RKRLm-*2A$ z9`Iz-LT#BXIV*EgMSD`^Wa5iYKSF0~3*LGAO-!FQMObcL_|y}4>&@5E-PM8bmwbzL zYgfZ&*1%2W z4%J%=Ji$1!^&}iQ)MDwL%AiAGSpmwZ3=Ns95RW=U+_o2FLZ6q9P+ChSuwT}2W{cS_Zw^^053}CCLz6~hymLX1puP+ovj*9xQa1LAsJ%vfa4+)yy zh=#zj>Ddp4xKrb#-tdG`V7Pz4%oe3Waj3GeCDx~3AC`-Pm}kz z(}{ciTA{=wJ`#Ad9~LaLob?Y@L7sb;sh*`uix27RnEs zSb7G-dpyYZY7q@+sgHKT6ZTO0 zsB8?pV~1!dpaPk^s+^FEcF~)X=!* zwAxTeaW?o}sB=+yWU)2JFj8p#;H7YiT^msrqOpMTM(N0e$=!gsjq+Z(7Bz)tI0~cC zsxndF4#44{vZQ%JG`~pvkmfZSQI`J|m4O?fs0#)XM725tm0LoLPZeJ3KdBFNQ(Fo; zlt^O@~SNEoj%>QH8)zJbOzztf5BR8Lf%<(Oae0u=2> zVo2KroMpeB+EyCM(#>d(6~IX8@a6U&W?z`B8PtcG;nw_w1YPGBc<3JGt2035VT8@N z1{HBNyp&FdhRVj~gwDDK&V&`#{8q|WAC0+cghO70XdDjuBdE$-hE=XgltgJfb9+$l zTn?p`@-$G4s5uOs;R_T}Ua&Eh66&)v0@SZ1s$rorHP}}G)OTtN^TocEKAQh9sqOUB z+<@jD5uX7*9o0weFYr*k%Cq@V6th9a1dcg^vRDKb>sr)@)go?TYNO6@F;rBJ3CC7! z^JdZVtN2fZC^2Ja2lm;!et5B{D)<`B=!d|F!G#1gE!cYA~#2ZC+A`i6*2jaRQ zlu_!Z>?tTT)4V7YptAPC8_J+QgXWf0SH09GtQv3cet}e%oHk~tZ?h8T?ai>$1_n(eM)~}{*mBi+q|-h$FwM=-(k$9IV#PwbtE6q93yBp z(_Eg%3M(Qu@?)nmp(Ec5P@lqtXC!13%XP(%q*f=5Cw5WS94@L8{~(-7NJvOX>>m2> zw|5u6d(S*xw)fQIvjq{w8fSvg>*<7tCR^+V4jd@<#$(5O;<0OKVd`zyj>){SqmD#= zX^^fOVKv*(g>Hn6nLzC}sG<~RdoBESt618qG1L84Hag)%8(jx2nP_kA5<&&u zD5G>Jr~6i|3utacZ7c_|woWnNbv863(@XdJ5O+x;FG=k65`Db}MS3XTSTm0;9hMeE z1aZg28~<9yL>v=(e2@1ONiLmbGVGf#KETvR?-##_*4A$q;B&sm&yxG@39T?1tofQJ zb{rO87tv(QZB-&}vBB)q!4rvLJHg{z3A<8B!krPNHkt&}fUWmuk&r_IzQ;}9NI|r` zn4T3Ojq=B>%qC$v8x~Uvf)PCu-gLzErErqa9Spd|k}*9^Dp|uSL6gN~nk+^V-qmgd zNq7iYHX+|tjCjZgi+>G_jzY0VTEM;>37Ww9eMPWq@(`g(YA`_pBu%`EJQ~VJFLG=e zw371BzTAO`pJ*q2PRW^StkoM1yR4qyD$keTh_0}#x*NN`|${i z+nv;Y+-Pa8$L3Azkd>KA!h}iGGd8|Zl+SI+gqY7w^};DMEP2Cy-rui~`U|IzCbcFi zUz$wwet$KIAoVv{NEBF+Pv5s{BZ!tzUAASwrgI`tOcP&f3trZSCBf1X2q0gzLHw{$ zn($Ga0?-?CD6ds;7_#ZRX3_3EJ|}|V0OhMs5EBL~2~j~W3g|t*DOL1YVczeICekLC z2XPW8eZCB2W^X_~2~ws2^|_ifaoJr_Kkv0NDW8gwPigjOH;_;lA|aRrP!dd>6(uC3T7}UG z&hx@(6c#V_L*%E@mo7+Izcm1pSx5a*4$NLFjA}c|P3vHYX2FzWfhLaxo_JX7`Nfa~~Ch9l&HsK4`awyu*z?i^Ecr|Yl zVg(*}GYQnc`n*ap&gD}ZiPCt^8pCYm+)L?aa*)Y9k0}TFaq8n}ybOA_!jh+go%%tK zJ&W2^km?Ne_tfqS3#dLsSBtt7@N41rsYU)pf&~auKN7TP5G%C9N#$3g3BVQBA?i*O zbxIcrp_=l;Y4^aC_Y=0dgXnam!*4W@f8M4b4s%>12*-pb3|laj@;nU*U8PuJUEub? zMty_Zu$2V!I6~n#A||S{G;Z2#Tj96GVOO)3`g#WC$m>eVI`TcfatOoG65JCrDK zxnYWIr7r<`5u z5Z0uHHr@{KIK=&**f)=ktfALmo#=}qD%(1mH*p!~QD0&7>!9k}myW~y>rcd!H%`EP=N$(9#&4k_(;OA%Agyyz2PI;hFqBMp2x(c%xUtCo0cwWYH0{)?#_WtR{Ku>W98;TGy(;S%kb-S7RbW;Y^p8&3%mWT9$CVXKI;HJscH+X4o&ns{|G-oWZ zk(|?in13X=p77qPF)A~jqi|k_sZQ{6;}G3vOV8GjK`hB<@U@-VCm;Em4N>tAqXCjJ zf>bX()YtG22C;~p%0QBN5)u*;|2q2bw|5si$vhtDe~ZlHC2%YN&7Cz_2!ct?Jf75{ zvkhhvppHE9NSf?Ng-Sd-*3wJ5q$VDln`aF@{-v$GyghXXn;&Ql zkw9P;#3BomppXS|*WK2;w3Y%$F11ZAz4elC&qPGhnk`S-YbuI_FvsK%lXpzOiG8X_ zc;#~z{LK0sK@hQa-Zx)vru4^2MwZW`1hDI~ZQqSU0L2_Fg69uj?A}o$!S+*iOH_rZxEaNhiIaia5$hQLDz1eNhj|` zMbEu9oydERi<<;zHu%zC1L_MV@>nB`-{Z1ip}8;?fI*#$6OKL{E57?258rtgCf)fU zRH@mx|JGaZ=PNFQ-{QcHm*0p7Zg~jnRxHC!f4Ts7-hM3x4;YI52ad+*k%x-%FN#Nc z<6@?|5i$!{4B0Shc-eyoWfn8+g`42tYJ{^o1Wk?sW)0mH1W+#M-@F!kCLEbS_vg}Fy0sm>pCxLNEpZq8&I1=6Fs8}xl}&+ zRLAmtT#g~Jv3Y-a@_WE(WAc~tO`VfQ=?%iH%M-%v>J>lWnS~4R)6(zI+Ej}b%a-8P zm!8A2AHEUG7P*ZD++63gX!4&yZ6*`E%$BtlgDw&-!z4&sbKneysoZl>XmC=RU4j6v zGKJvrt0>JY;0=^golk>OpN?pL0ct{etTXFT7B51GCb0g(pji47*QC>gmV`pP5(cU} zA-wv$4ic)VtsAKhTPbh6R_bqZh4xyZ`4^OVykhwm z|9GJF#i&gbQ#{tA*hu+dqzQYF+7N`v%w8R}&QP)`j@sYrxcXIz! zgoKIu!=Q!)5$bbzZ!#D4DI~Clio(LOAd}mrHV=&rZm7L_6fij(qPC>XL|M#>P`({n z5)O-<4(iY7`_y+O0@PPADWc4SCqE#xX5y88xRe=!@Z~nleY_y7Nr2@#!TnQGlefP- z>x&TiV{I7r&;1nly^e?hsgX>4=U<283$DfI?vLQ|kuaaL5y}R$Skh>5novmT;WFnR zIynD$zgFIN&*R}Gog4>h|5hgnwX0|xt);#t6>(o!7(OX2^o#GSXiTv9NRYQ?qEKr` z9i^$5gmimAjoe@sG|p@!^eR+PJu*_Bx$QQD%sQ0NH!Ln4)E)~Gx>TW&74_yo9gd^g zxK-@k$4egB@@d$#6}G4WIn>|B)zk-27-nxi^{v!5+nK2Kp;)&Gk>YA>QKq5Borxf8 z1i4lqY%fND#%8B2Q{<7|Oye7s2@|h6eF_XTF6CRPEk)}nJ!`Nj$42#IGYSJS%A;(d z-JA%z5s$b3~jJg(;qK2L7f z@ay{UYdBcblKKN1wHFhmn}4i|I5*>s#A`Ub;a)6ud;p`>f>vEI^f8K$ZKFtIr9XkZ z#BbL>{!xLAi13no2jxRBkd82oy+-3kK^R-j30R_j82nqQP0{31No|bAB(-u2ihY!X zy=7FL+p;Yh+}$0526uN7+#$HTOVEkCYmkY%1`i(G-QC^Y9o}4f@3qc8x4m~?{h;v= z#`voGDD8EjiUNq0r26?bOU2;9F*by#>Y8YVpPfp>MIA7y!Idj~5HOb-0`3Nzo^jHr zyeUkNaOJ=gFigs+-60mR&j{xWi#6+Ztf`_|Sk#_y+`u90n0poWjF%m~?7~hUFNZB1 zRq7yaGh3V*2dhc*rgmkV!kPQEy~1zVhzX8z5GgZZAJ=qt+~V9ov1@nLZ#oVRnh1j! zuy}5cq=N9u9{YpRISii$sbjcm1L1r|vo;&Z!U`BQ$z7AZ3mVDpKd9PB^DmPpj(K6^ zLCbzMTpO|UATmX85v6 zcZ*#9T#5_q*SC^*0&ASC+$G7ehLGnjjSYh=cbM@+K6ZNwP0|qD>j>^B%X6RM#z2}T z40(nUN+_~A?r1ZD3JvYP<$0@4pO3i3ghroiR_ROrv=UJwR2O7nmkLEa7i-Z80U`&~ zOF-B{9b1uf-Lhv*9ryMNJ(dabMJ#NlApvBWP0>LajtkM=F+}=8*+e%mqoVa&m9rnv z(8`mFnhw333EqPC)OZiTud*NDjC!PP?=B$NN(qd$A*+JdbpQ>J0>~eT z$dlt-a+8C!__VC~P~mwdm)oPEy-02hHcc_TerDFn>x5c#ntxU>cDtsWJ)U#!Knszb z4=W1^4PsempRkk?!vQ!1a|YtIR5KBcqV7)ywY0RvL;CB$7ZbndK-E{|_|ql4y2Quj z=05Ok{m_~c-6*9okn5$z%|xqnQ*_6E_F3WdIH&flK<#Iw(SOG8GRVi3^=fcqpE1#+ zKKDFIdpI_*Zs6ZCx|XwWN=+0^h>4W~tBQh@#g=zhE>bbyI z?nWT1oH@R;mo!0!EF15&tTd9!YwpTVV;_gKE59{|&_j;OXuaanUCN?AOQV3<9q3o*^HO zl}V=1qnSj{{q~34`H{Am68xQe{ZNp&(oZg1uKS6XHlJn~T?t+I3zG&7ij@*k?vQc} zyk>vBBql)V5TyrL7CM(HkI}ArCF2tpR369h_09o;umLlXN?OWcPQ;vr)NVRI3KFR{ zlIoBGQZ=Z%U0Khk%Jph85Fr_caoG;$8`<4C! z4KYEI6&B@fGFYBcF^ZiuG5n?5rjpQ}oS!Kif@F*wj_YaQRdY)^BU%$p9exTcp6C8C z*$Cq2m}?GFv)~M#JF4z$8$_uT1$2gBD!|cZ5=%P~p8o{5C@qIyr8E32Qmkd~zhGbB z`YS+1=1IQWJU*QleWODNZ@7{&9n+&uL2wg$Z7#dQf&Wmhc1kprsr{ak5=d>cMg)PFqifSFVC@aP5Q$Ui} zXVrT<&&KF5D|@8InN)mTUkIsq7spVeC|M6FiK$V<8#|!9OYIi+4}Y%n>cDE|)NZJ?4A@P)PaaCJj#`+MewWoG@?HQ>=e$R-YxZ*OM zVrq!sP2n{l>hraS^H6TK3SV8t2V1P_87^241styG(J+4z4{Hz0$v$MFJUF?#b|o-T z4`I}w{_yr_u-N%J#he-}^(9@JmuZqV7eQq;V3tYcW9UsOh9`5m61|W3*j$x|+5Ngi zXeKgxu2D(vptK<_?kG^OAW*7rq*#i1-VE-H7rHohMW8quj+fZiH&eeOWI+5aP-a1< zQ^`AQ8n=5VgwMvGDlf3V84;kwHb=sQ2&D=$H)|F-+HF*^ARNFBXTFM^0=wHDJw!*m z0FZ%Xf~!@MX0wkQ?m+RkRRudw>CK6p6!y!%P$6vAHfjU3vB-{1pLiNRnSi5?6xRMOJ zEye2R0=3||Y@|dgJ--Z(&5{7T26O)C*s6Xunh+5vRKQ~wleo+6V1DWTRrvI^7arw~ zi3*}GdRgJ~pwO&Rrt>0Ny)`NgqL}G*x48ksnCvc41#gP5VqDCab&Svb+|YOj$1trb zCCP{`2z4)W}`5fX6Vuy4>bRMes&OEUQ(^KJHwzGQRrF zkCM02O}Yl9)USP6X~aaap3u22wvDWgB^cgPsZQh>>)6NI!2FbbjdFmwOND3-jek%~ zySZ^iZ8oYawMCSM#8Fs}iGrAR31&NYy^1&dwHTD5_?HUJG9}dTsf?izodI5a2+Q$F zg{(K?OIG#ywBL)ho42=CC#;s;H@%8M(_7MAYYUm-rCj%CqZKLUgs0{=x# z>x6$t1_)Ey=ncy4lHAFmj$BSBsmUR*ON)dlU8|8bh$)4E@74F6>`-z({Mq-I3)Gh*dl=DXZ#imM@q#;tlw}_wfDMo#AsNejA>Ax& zCBFm=Di}lEMP~TE=9g-0b$65Bz1Z>op2~WMQvDZG#fJFD+x_{rTRedO%YLD<%~&!u zkY0m@#WXh@`wyS%Pj{z-ajcHSt9C%t^Rq`TVBnw?5*TgF>~6`R{oAzq%d<$t)~ze~ z?YOgA0l5fAM9euAq-6D1nPOD;Ui9zi_!_k_-)EvGR;ydy8kl}2|Pk{VR84RAN4L=!xjvny6vqAoF#CEq72I`zuHUE>YG)zOh z(7F(OiQjtDHw*X>i{Go?%w>ymN~59qakTIoBaMF!o}61?2Z^bBCM+t%;7OY56}gXh zV`llVUS|Esl|s_sIgCz#4e_M8$<&`1B3 zcZ4Ej0);^??DH|9>XZrBinM49rT%M#Eo*$-cS#J1v_l+C(ds7-hhB2UV%jNOQW3dq zI9pQj?mG0sd(6cB=IW&3qCr_vWPt-pV?-*0#}+~ys%!TP{w#~73~fan`R)oqKMns> zDmUmuHt@~1(MR5#Fap}|ys6f`Ln ziP-R=RKZX3g^L<%7m<^_M&xkLGHA%kZOTA0d7q5)J?1!6EqRO%W%!xnVgKZy5&A1`9sI!>marHDuRisE)2sgdPg3I=BuiA*?qv5cG<}$ z!d9GY;B;>Sg`TK|fAsNZYr5;8L=GXN#BAtwiKzCoD`mXrFZxF-!C9pIcIZ0aQh8~- z(&ChM_Pi~0#%*|ufB*P{)({$OCQSzCh$aConoJY5>`Vc#YxHDDA4;_y&tSAcmSl(o z=S|E$-OEXCknaHa;2^mUP*Ppt%I|$-V_nly#ZiatN~s`+{{7u(XWu9roj4kaH!X_V z#&UMu%^dIA-tU;zx}VvxZ^WR9xUW>N#*9IsS99hr0c9gN=J=cdG|fjD3`+D+OokPv zCJLexYCIYkr9e69$&-hv471_Dv0}$&L;4`W+483B@HXA5#(IM`6qvMhOLlX>q0yp4 z3iwzhkj+;Y@ZzDs(v2#aryR2~HFJ_#=qL<;2Yp|fyqaDht*6s7lK@As9&i4FjBMA^ zVBgeil0LmrH2PX~v4g2t5RHiw*BgIb=`V4>Fat-Cxj zs1SBfjubZ^j>DQVCD+A9IG2ers40g}+Li-B`j;E1kzzn6m8QWo{Ee)!jFY^B8N*6D zzIxuGnEf}@EV?ISy(zp9u0%J;;)eplXKZyNgML!IgAI3}&KV}4uxLkUOt1Vkp?9l= zbKhB%FBpBTMjv>;_;u+T-4y3;z-zqY^@i=f#|Lo4oIu%1A2~qPFgpnNm4A&uU4oQw zX`SnOVq78mi|ff>wwGT|)k7`9^_00dVowJSz1mq-@Ef+(M5S`BlG&}LqOmc9I1GO3 zr+OPvdG0V}5RX(cCi-y_r~;K!{M@^nyMQCSnhEDQ8fByaeQL#LC7S4~XNB|riBMJD zSc?tLoMKdoZ#bWSzs=;Pg0`k0d}qwtcaUA8!ZirW!dQ} z$x}*&4jlcSE1D9XJwl1UNejVy!37cV%of{WrP0WPN_o#dxs=kjQNga~>4c1QAST;6 zrE#3l$#Jx0ODgKSDd}HaO2-K|H1@h-%9`A^KIn*Ck!@5mfvW06vlB~Rq9Y4B!rdKm z(b9p?TSjzIvms}CT+*5RF}B~xE|SEby3&NVNTcDjIF)zuJ=xVRfAVxhOy`Lu23bd^ zbLfE2ZV+r;o02n`d@HpqB`qRiFVglRuski3DCC8g;SQY6jb#JVz{GcGKyQ1Agu#f z!_QG9Xht*i!2N~;ed(hVbpqt^nO08>V|e>e2q|d^qKA?&armOAPQJC)mDg(==DY`8 z&k|$2)eEG7A};(oeI0{2{o;f?kq!B5`UBv&f3WKJAFBHRFc zD80=c-!1fELg2i>hWyNFQ7Q`oBB}Rx?!EnD!P)nWRLevgIW{?d76 zhmxQ~n3PKw!n!My*xJNB*FhXe5*e0TcArThqY%)hJu zO@qBsZXwHjMy&fJ zY$!Dm6eEZ86=qX6RLQW6|N5y2nYBH>z~Fdno^prYD{9ZiOmHLV@QUVbf_VoF8c;jx z$PB+RkSy>JWoOpaJ)3QQ)r6thg-)=q{{p8ccOuuvZy%mr@MgVzZ#EfVvrV$vtiMG< z3P3c4;CjvfJn=1qKa16Ws(Kg(>$pS`vu(OW13=dr-oLPpJ00b=@=}|Gpbq|DqW$6 z?Aegfa6z*YSrQNr?wF5(H{tMu=)Izw);G0}w2nAQbwN`*EgCZ^rNmZ=#5#;yY42L} zL<(!ZMNBCTMX}@iu|n>B4UwxlW8$pO$(N38PLwBYr2IBQEW6`SBzEk6(SWG!Go+>u zj9#9-$k^uy=6W8z;Z^tFD4k~kmCCzuE2 zx?`I+dVqk+(hE%NMhMl$R#2u$Rkc#*1Av$i2a?CP!;X!0-Ph<*aq!B-G%DtgS)@oHbWT}?riBJG%U}Sz_3PE< z)V!(!M7U>_@Ay-n8fadI?ZNI;@4Fs_Bs@0pGaV_21Wb=vDZT!0I>%9 z=ou~$s24dN!|5oyesOHG@w9qi8c;@H^SLd*EeY}meC)&ejP+M{(Vf_s0NDJU_4f?8 z*8PyQ^}?Y;)Tc&oZ9MpGGRLY8@SkyUhfo-9LxqR3n^!(@L*&+t|N9IT$q(}!~jqG51DqOwWZTV@_SD1E(NArxP zy_YN&kB9`Yms#9o0a}Y?mD#F_^S@i<-8nas6C>m{m&#i_fMqft&TSvw@b)=TLGdl8 z_uZUVayoXjRY+;%?_LIUOZIM*cU`mo$r?}2T=2ZRsZ9(>Z#`^gl>Uz$oy zR%3lh94C8tB`7Qv-CCeVoZ$7=M*i0||0P#dffXaQpkY{{#71AkC(}4l5hrGtv4Pgz zVj-~af3b0FH%|F>w6rWr?c)*JiSV;b^+K+VTE_Z4c<$Wruoc7p4jV`f!73b0j zK~~UeKRz@s(tJHY7Oixmjt3^C(#F{E=atr|(Jz_Wc1SM9&L=|$i3vLHTHjOOZ=P6T zjVSQwP@z7hPz>JRAMih3tpi&9gHTUNz{mg!c{2y=s{M?8-)%*uQ5fjB| zeRL>=%!NP=A!vRrGJ2=yhz^qdHcSM)y)mZcZF@@1T}fKDR4iA=hUgwbdH?(8n!IXCOV#B zwFd813S~XmZ-I*a34O|MkuK&T)EL3BCI|Ss45gz+j(DuoWJ{HZ)t@^)l;fa#$y2e7 zr#-!sKUVV1Qbd-1ZBO5e+lH!7BPqS2ITcCT@XE>FS5F5un3b9+IGp)5O-ICmHFZD> zAbWlH?-OlO)|V#@9N4g=R4u_mGj+&mK_~qMR)5K(aeRjPRcmB;+b(f`4XSqM8C}Z1 zJNyKnFPz+P_=Z|@RH#R%2Oy9Q?SxJZXU;qv#~<1_iRfqjYrm}w|Mmjy`pju7ByRm$ z_p2ON&V^%9O^sAh4^wRC9zGHKtD?ScNbn7>94 zUb|;B)MI{jqefgqlvEZtNavMo=tV3a8)5c(d%oQavr5~4*;D#fGuZNb8*m z|1Y-FXVaXQzc0W1YXogq*RYp-JfW8u^x-GUZTFqD4JP-=u}kLZT!Rh4Y#J;8wrA>sAwL}5M{ko1wYl@quw;ExbMYZ)6f5s*ONh%W&^HW zIJ_xSwa>ep@S?G?BG?o!SpNrntsBS64S3fQ_a-hSuz1d^f(Wm5WHZ^IW^hJ36H{Z2 z&NGfuSYDJyvjhlk%!Fb9PS~3@nlsGy^W+-LPWV|VJP0@Yg8m?`9#jMzhR!Iw8D^JZ zSx5V>fB|Ovch%AC2gKkv?%+FaVow_|v+)9EbNT*^W)&9C^ZXQETkI_N?Ju&atikO< zBu-`%y>*rd=`S}k@eKz9b z9`(Cg2h5bT)BQ_Ts3ToDtmhG}irJWb1?%g1oJwrR7bzDv@?!<12LPDsvQw2LnXjl+ z3IL6ux5w7z6b^6nBKdZNT62Ecg<2LT+B>vbI43H@_0iIn-qodsg!KVdPy z_Zm%O!HAXh_!NmPKxJ~+%tpPHgoAB(T=4Rol=@=y-YU_@2VX0N;5&$vpafB-1XKGB zC1DLQp$EKd4zYL%zE&5mR!(6-O@khLE7XuB)sThPpt0Goz=2Snyqq(j4=!*WzCtZ> zwUs@EUc7`|+QQk2J5#=C&CX*1KA{V-We$wZyT_Q{ND1VNv^ZT0O-Oi=F!e3ZC=4QHg^+PG~+V|1!4^r3T`t*v_Xk`3Pq zS)*l}o`P-4N>Tc9C7P}+h_Vfq{E&-mv)*7lsuY*UrfG5$=}~r5fWs~L-M4~yYm{vw z@!wXz2$3S-Y1i@apG$hzkj-%59OvDU)p0vZqR=;wv^~>lSjVa)ZmH2vZDtY$`*}7- zOOtYWtvRY_u0l$YQg%nNyK*{tj98scSZzsPz0AR^&CZ-!&zyoQemI7GD63{6$5}F` zbw#hzKb+r3qD-j^i&41y!Y{3(YfJI@*;7Jv+ZSqeKc&?eJvMj2+AWLC zuxf_D4bCo9cGuB!yTO`OlV+6vPlJ+%cuq?sF9s5545DWCHGE*-AWoDFu{|Yv$%yBT zaSA1V;IL}vUw#`12zSVa`2R{j!G#MzP~G%r|DYXD;U<215;3%CU_QqPvA7{`e>dG1 zgnb?p4Hxgy;zZW1O3tLl^cyz}?b`~GAMxCU+N$>0tZOo0!wbI8`egl@a>lGtKAA4p zT{UqL&{q_+^b7rKhPW+inu}UG7=AvyYb=&4b%Kky$UV;)af*u?E{7Q|621jH?cq`WNJ$#R{B_8-c|Qwou)uM|%>J;f7+3cU zDyuT_!&yAgrdKFjRtx3;LF!k%{6%sn^~2aflbO(YwNrKtc40l&RjyfaY?hcQIu?GN38> zk?Cw0nP#yYo6HyX?*DB{8cu3ua~B%Q)*%}gP?O>3S+2aUIW6hqZeTeCXSNL6VZ=FY z^$-x4frhi%o3780sW=FpabZ01z&0olO>S2;*^7vbZN^aRJLlP}rzESwUk;e)_6Icu z$dCI=YRny`!*?9}gThlBp1)jrRJ8T0_AvGa*nNdy{0S;?r+$Q3EFuGSVW6zLpaMlq ztP*kER^xH`tRThdFu8-Og+yvlj7ezj^LG@x+aaNJ>5!@X-$@abPh+=Uh$44lQc3H) z19I2f>RG3qdZ*56ddh1$%WFH0-4ZS@{JRQ5*Nyz9%!Fe&3Dk^{z4TzNRizgNz;Mg$ z4sWqV_JiBrJ61Z%gceWbOJ=p2Y|M7ey<@W(_C#A0^VPZyFFyWKB0PQx5z~pm}yri6MD>QW{*_@F!Ob zY%OLKm{TED4abI*A3<|Vy17E1W2f{7{(U`UR|8`IZnQ&3_k=FacBP`q5(ERW_(m8^ zO8suYaIKX-1r8i4n4Kf61J?^C{JSkUMe>y+z3Y&PSP-lD+2J6SIrc5q3dd%i0;Pd-W`1HN75}UEa!6899j)zvgn6 zLnE{SsbRx(MY4flpzPN)-PqcBN2mYGT#7Qy}ne=~TR=!6$NLf(KoU<~6=2RG7s=D2o4< zLRR~dYQCt&aK0#FkpJoSbAic0*EVv`KB91XvH!-r^{SCNY|8gRHr`%A09}=`!3JQ- z=z~9<69(VBWW$Yu;$1ywfn{{ln?_SRnL**^dij$Jp*#>y1ZW7{Y`Z+2*Bhy8o!VE4 zoxn25T(QF#*-RZZhQI~oyEWzjUh6i98}`1B006!5)?sjrTo&VXJnX zcQzT#jE)7Z8~(PWU~IU4<1YU}ucy);)##%a!?o_XdA88=ct}pr{z?zs*Xdu)TgQB? z%ZyiV#3T^8gp|MZDg8=fmCFNl+~6nY01CNnThnG#CUiY5Qd$hr z!<={amkqA&(c(w$59~s|H%46dK{O5r%jQFwMdPJaIab1v&R}om`QQ$v3Ks92>c-K z7J7PtVYNStdRk<4V&oLyglUeQ7&zGAk2Sx^>R~&^xypNDa@T%}XHu z-0rjUdIRL?vrgFjfMaFqvFa}ek%>JuU!Xc#SBvNSD`5yP7pXgj8R4F9D2J3sWjm~e z1v*|#+i>f+F5*lKaA3q>J1U`8ixr|getxH}5M>+=2YIDFLINeMsVg@4 zAIJbe>W6R^hzW^WE61TWG(f6&BCV2SHW$mK5W?D z7sE_xvdCZ5rW+WVcOZ8-5$p}5j_T{GZU3s;f$0`a7$fv{Dk|Iv7n{w6jzI!Q@1E=| z)(SSIv(>;D3w>|lV^(89mr(G9AXbNRZkBPp$fe#X>a)(B*a$$OLhiFvU^UDYwV0u8 zz23)AG(Y$}V>NJt64MiO)81|6hMy=j-pewu9-!beD6W$LXTAQ?v|nP_^l?VR$| z-*zOScie$#O4ESR+C>gfPdL?96m;n1=#8y6LaaPD$pQV9vC1Db058&Ok!lK;Z`1%2 zH|C4LC1ZqYw&AlB^-dZkZxFk6&E~NR%XtH^#>)vh;K+KDy?~rrBJ@sE!SL`9&fWYQ z)bD^oXZtVHRYafqII4`wR>BpSmQbiCG~s0IXu+46rv+RO8F+V7$R$5+r8E9qw7Ji> z!$~I)*UFQGdF~gBrb|CQgIJI={cq{%)ZTu7k|1)&GxL5CAS_LVE$gX%ac{1~;|(RE zl}?bc@ApVR?~gkm8N>iR^%Q?QFrr54|Kr(plSuAsjvgzM*bFcJ%(tko9^I`vOv^$ZQ|l-ieWhH=A8F0#FiIThP%O(TeU!c^{>N01wrP0;wc*q=Vg;+gPI-Xn%J-SMT*FxOv2w}s$- zj{YZ7Sj76r<14=O72ZEYb*He%u2pmuuDN#sSRIpGgM!88I`M2ik2Kaf8Y2?DJ{(((3i`7z@{B&|9O{luntw8MfRV3PN1h zkBbeFrtYx%%N>@E`{Gi{-H|@C&t#!HEgO`eFYfy(zec9^mYY?4`>nQY^EDz(r8^95 z6;W5l9P@I%A_04~_I9<^%)387D4~H{iWQ}f`(EZVh66v;}P&oqoxkadS2CFY?xPMKee1zWM7j3 z)PHrA1yE~&$~wJpc<6%Hd29d!;4`SE($&1rb!@geA$MNR>~~p62b!J?Jl<>-8}v(L zcOEhCjJXMR{T`#uT>`${sSTc7XtWI$Qm?$TyEXH7_M#w zGQa*_sA1O*j4F5TRTqj?7kq=l8^^>v1X1@Eo#b%uK{dSz&My9rx4tCrO9@rY$7$#l z`biC%Ig$F?_=0*X{|2vcfncGy(b|;L$-}yU(V32GWKj|?@QVQw()%eG$&q(t{r-+_ zV6e=k_Z<4G@*i+(dhyrRKge{zM&q?VwB>JwdT{{p$RE_HKz2VvCykmV!~TF8n= z9xP`bF~ZWIP{y;#5xtdC)FugFYHUHe)Q#lFY&RgUuOhl%60S645=E&(*gw{LWVf zgdU4fxLk%b=S@$aGuZDxd$o2)Bf25emOB>s{2;z3U`3@CxEG*B)Eum)sCIc$X?hGw z$irzy4p%5GEer+CpSiuXPIHHm_+e zA|m>nBNEu_*y#s`%k4l4BCMgU#CtidofyB_brS5@3L%Kg%0dq9AsYk-js&l+>ZFXB zIlf&8lfVn7=Zn$s;b&fzTCyoLNyp{8+X1~~?x zVXct3N0|_2*_ZaJ*FtI=foW5Mi0y%|UH{ZFN0kf*>fiOnXo_+TeqWDY^fYMHHe|&+ zT!qY(7qgx5A0KyhZ?l607d%FNkC$A*+8@tiT=x1&Z?dp))Bf;|b-VFT@ICdnmh@(I zlYHH;VXj;_3054}@{m2g;z{`AH5Rlwn#vaJAZWA5+6rBRkEj1Zj3dr#x*GqLIXKXrRDVOCEv#l4Y7z{Y4$!_fI4ZHC9VjOe{DFA4`gLAF4|yQUAX?|oPVR|)y97#gop_-hP_>*cAO(; zx^1x;5r*rA?}vb0+nt(h2DcLIL6mW<0Jhtj3(&p)s|YEo-@p#q!7HQn(~&bT8dd1n zL+a#l8YjwW>XOFwoHzH=qi2otjC6@Due)xS&&E;Y?JQ!7EOyPoT3WRAma}Hg z_oA&$Z!GS&ONgs+uJl}2aRY~CgNDPc-%Ey5E1Pwmy`KL%R=bwYTW*IN#XWJg8L{=A zB|9x-pwAz3aW^+=P*Rk!NG|>JVB-eD-)Q&x@Sk}yP?!tvi<&xs?<)I;C4NB5o&NP; zch_J%gXi(G2PHl!2`YbzCdl=Eq=1B}_zg5YcLhq&ky28ALv;rL0G|=>%jT^5;(PY? z8l-YR^n?4Y0$62&rwvfSE~E?W?z>KFyLQ<{%8sH}DmR@%H*Z4XQZvC6CZW=2J|$>I z<}AQ`_dsU7(@R+eE0MDT0q9sFay^!7BmuP8hv7RHS!vhZe?FGGWrcJSHT(4sr&_3* z0h5)#Dvy3(Z4_@E0Va=szj});|K+<2g^e0dN5k>YR~m1})E_^(KkWgHPZw*r?`BmT zcjG0tOY&p7LA38N#xXqN8L@b5(CT`C!pZ&}%6e}O|CHGs@&pfGNW5J*kN5@-BDFSR z@i$)Xa=61$EsH3v=a{w)w`b9G>mWUu12dx8KQ>LRoECTZhjnI;{EiyBV7T;V9?1xi zbDz?eDDSs-@|Rv$Ot#iz-tUJ_BL8J)o%nz)hq&RNaIQ%jS|j)#(1FMR0MA?djpsiI z+eYxu!Bidt2l=ViH3DP88y&dmgPioVhVWg6On=MXeo1Om(@uaSvOZ$D8c6d%1l2T+ ze-fH>NJY23!{%*3l#S7J@3}9Xdf?t-FA|y6d;pi8SD*=7&;2GFYPD!=)dDqKQ{v;n zP}aB(0dRRp(By^Rs{;CLF!2Fu3F@so)gPQo^^N%#KbPPCZ8uHrZ2rK^%rAAfDU-%> z0u^dDM2e4h*+%hX6thEBBbwJ@R{9XJt)I^os$~o^ zQw<4}BFv$Nj9iDe&4Qkigtfvdl*tbqD+rw{2$s(e?mG+^JM|ZtNb_x@*!N}oIb!*N z2TI8rUHE4mU(Hu&E9&Y}!t(2xjqDOz@3TC69{iU%aQ$uiHN}@8#AY)a{j>vGD%DwM zIa6&h_1RIt?ObOxTZlxZSRU&k+vnL*Hd~M=fm#9kVF^WF2(+$oo988)!x~!-+APwk zzZGy3Y)E0#fcTo%vsOXWS3pTP{y$oGusZQr+*bokGS&bEG$Jl(35gGH;A=^UwmIfVFApPwOaE;slKZAjQ976b~}Wc+sZMGo4cTc;21*M*)C z-H}9k3kCh+BK9pL7R?7{s>LfingEgTdS$OiGWjNs z4AYl4hFCx=@$5XYs`rB`#X;szJH@Kb-(Y+C{l8yE$^H7q#{8BRf{Ka?zOPPUCzX|q zj#;e}?>`TZj?f->`S|)A)$ItD6=%mKatvVHT* zYQ)TmA<6yLI`hrK);=$`A=m%h$$e3N0dtJgqcHmYJ16g<8C<7`V&~`m+txB;zRXGO zwOiW=59%k|^YU*n-W`#44UVjTjzs9zHZRb$w9*DieAA32&Aq0k0`Ies|486uKw(nf zDz49|bS9FH*Q{rhijY%==%X#_`BOa)0LTK0A-*XUWWTYcX{Aj~4WW2$fO;ja;@XwI zPAnfs9R1dA9Vf9Wwa>SX(S|urJNc&iHC)MSawa^+j8VP4#(H3HXfNffm{=gqO@F`m zl`QYkvy*HSrLI1@{NKq0Pn`d@#h(BvAjQQZg>-41r&c(Ioa#ej3^!Rhjz+co+S=svhMfEsFk7Oz0B4Lk zWlsjhjeu+HqLD$D#Hm_d5hItd5>BOpAt!2Yb!Na^0OYC7Ss}XTpfTN(@#l(${9NGT zPV97ik43?S%dNwpTmXjg?~3;H9nq{sV>jTVyfyXP*1;{0v*NGAy`n5LG;wQ;1jn|E z#(KB>_F_0)Oz2{zT@9pfC51uV1;8&cF408W0`T#Kdknsb7?Vr>_hufzSLf;USE=!V zgpXoO-n6w73TIVn!c~SdsY!soY z-XCSeDEtZjl>4l!@BLIZLx`JM=4v|)#p>{R(Qq{H0guu!y3SmA{@ti)HoDQK)?XlK;i2Fb7ze9pRcBhx_);4CpBZOoUPfuvTJ14KN!?E<^xl2ZmRnTx@0zBn0GQOQm%aP+c~~(ccHj6 zy)bEC-94lJ@b2u3WfbSRL5RjIZs43{30zpBA8a|poVd5e3ZS>Pgi6CtwV{PfOIMUQ z7Sl<8IepV% zvxhiDh+Wm-wks==KKBI?i=f&EHMovPYSlpjcfyP-0}DM`NRjv&*(&Cj%A^Lf0KxWh zsJ4mlBEIv#e;Hhy@p@zvC0I!PW<7;&;?8ZLU zRv-fy|4TmfjnGOMYZvtu3Dt7iVVw%9i!4#YY(rk;(Jy3=`S~Eq5#P?h1ELsz2rNZJ zV*eecCL)x!8g#1Ml4O({IS7aI6YSojpY_|5Q=%6&>x7;;H^}n#9KTkpwkG4Wb2}HqPaPm{gG}GA;5J(s)zT%D}v`w>w$5g!MQ4|HNo*HTrL>&8WfD zHNs7gx8G8|TJjShp===(q?}8^l>ZoRYVoz#vDX0H9t7w@uh7|cTsOl z#={e?dAT3kv3&KsTi^w;pRP#ykDZ8{3(6lY@W*3d63x*b=a(4FTs3JDB2A3nO{I}} zT>uTx?vPuk7L#V`2VvQt0IxMrQ1c=1s7{1oC$#_!O8C1Hy8hn*jK7JVeh<#+W7<&L zLAI|?aRV*}pOhTG&v=>+0uCeQLdOxWU&Wt7cjqmt)>_7>MlMgs0~xE;rw|M`pToZG z?^>;Og@}!9z-WefFOk)xMzEE%biYdUu5FISIr#Yq;P^ZO5+C2SAOI;s$$WEYqCKF| z|CN*L^YaWmzt023t~mVUluFFr15qH``u*qOt3$>!-H?_3B38d&mFs&Atr>M}_q_7B z52&Bd_KXzxin!q)iJr~W5io3JiCGzzXa?Elmv`K(HESoXXysFwi8NPQ6lava5VN~* zPUptAs(0S*f5UYFWi1`OA-30aEf`<1?Kixzx^B#w43Zht0^IS)Hx zQqCOpMdo9<_Ycn+jv-@##@byl!}nT{DlkLshO?33L+vj4%7;KpH?QrR+9B)^lIvNw&R5Uk81iVq#L1{%``w6^G(us zR2wZBm=yD4-A~IDm?s)Il^MVyY^E+EV`#%Ib2AaY8oTt#MQeL>6SXM)BO3p$ewL=q z9>uC;-3lUW{WO2_hZUFz?}vdUH#rHtM7;wOoc2I+iS;Nv`?W|Fam3DQr5?wNbfNrk zuBnrynBNwR@6Jz#i@j4AT{jd%J}Zoku@#=jtWokJ znJ+fbh|u~jGb%rXI5wTL?9+fc_jBUP=6JDW4!+?DG{4tfDX#Pt-(^_s)%Jm9$#&Gq z-oERRk8X$#%Jt2Sn~oHin)5#>LS3Yy^I!z}b5vxhj~fsZA9p4mC{|cYABp*tP_Sw(-z3PEr#@qx}&oubk_h zidFD(=j3hw=5)xd`pmqZej08yLRxJr2AiS_W^?maG-FKaEk3iBG+Gaa6+3GQ^@kYK zCV@2?5tb-*qTm@J*__n&J-r{C$bzS8<(H~?rTl)aQpUMWUU>AF;@Vv=+{!GF)cmzz zD`hl#HD8)MH>KQZYKgEg{fR#w21jS}fBw!X=Z0X)cSlQGFcAmG!|3_d^I=}_ zUt~lYGwK9n>|0^hTVJgz!9$pIl^Xd6V9yCu08>-W8 zbn`$!Z%-h5^hW>^+kXtVfb$ye3Dr$TGdB2W_dz=ir3S?tFs>8#PR-XL)nnO^HA&g% z(quZn@ldV)tYm_t{wLx<_{URGd3+e;kClO8B7#aC7%_YKiw~wggUvjK^d1_~prTsu zwBrNS@$~4ZyLLh_`e>#YzT>aKssYe%7qja!_#;g>mRv=x)o_g+W&P$nb4@S7b1C&- zLkaa^RW{zy-8yVK7x2XSAJ)uPuctj$8!aGuf6t$5sd82qY4E*Sf~CQe-S%1er^y`{ zEH;&DG-f{4dd${iZRV%j_c2GTNcJhERF;YJ0oZl&J9+F2A;yy2xAT;^?*$f+Av5t=Qiz- z8eEZg9BaaW$>hedK3Y3=l@^v^_)#3y$--8vB>vFgxa6vm>g)zD*CB3pyG(-?z1KG4 z&gby}RbIK5c>O~k#4H@rfIQEXDF5gE|MyK9D9}>|x#K)k_q@C*(^~>Je;^+-t`74P zdRa`?j2015s8uW?#4uSq*XAxBAewL~BL=aOX7);>GQATk5V`To zPuzV#+k$hf zNT5EE?QF5gGw@Zucj2}qpX#$JB4E!>#)+kF26OS^de8ZLtU?u0EL(d)Q*JqzXNygf z@kg$^tlSs7DWl=AEBB~{Bem{V^*&4TDv;q;Ds*5*#QT0r8Ocp}xPl-gA@&oi z)TX<~-EA$kv=#Ft(6uSA zveWhC`((2JTz=c<^lDv?aygOJNLLEHWiaz99U4$JMG#!a?9Vp0`7~p2Xa~j%AH=C6 z;RccJe70s?IY&R(WXl1)%B|%OBRFjI9$`24|1kCzY;|=>w`g#J6EwKH>&6`d!5xCT zySux)yF0<%*;sH3zHxWAT)Mx0`#Vpc`@DVXC(N~G%~7MqsDkH5uG=nGkl3a%<`OG` z&eh_>*-35po2990^@5yy1R%77XIT0rOxc%hLw16yp|3alB_l{Ly}!!$fhpK6QV#1q z79k`#ljU`si{jn;Ll;lnsFqyf*eMv6`?YE4R70N)CQ^;X0( z=biUL^vAjFGpAf$&L*XV_8D!<{!V5?yQfkQbUj=)ETq0^o*Q`vMWrb2B^E8`>9)s! zUzZ$vTOd-3Eq?fH&N|~w3Zhr)7#vT5q-uIIwVr6^&~?G1W1+I{be2NY9|yXAhJ<56 z_TN#vdSv39_&Nnse}3Uh-k$C~DtbMus>K-8b~a>hcI=kFgYCd1`mxjc)PQ!UVVUiyLB1`XA^GZH*xIMGoFa zD~jXv+hec_DKCRRTogHJPG2iZkhD*aEiUG@UaRY;y>4YU*JbN*9exo;ld4#ck`*=={M#Jf&`KPA=o5I zgexnW9$yps9>?vxTJQ7z?~kS^JiIE7XZ5j%!0-=O!jM4miC&8Ks{ABlEmq8(;n&ZR z_!LPl$_7JdY6c@vn}vQ4EtPXSzo^`OO@z_G8>q+B00xWz_p&xt?5uBHhND14BtyH&XW$ zvDFSFUgdJXwa=M6?Fr$wRqXWoG@3i}E!WnX5mm~i^SPn04bvE%>?XR3m~`>DA~`O%e#L-9y`>T|%JJRXk^ z8AHc2^V-XGG`8z4C)FvnaJVV;B=0jEfX3b3o(Jxj7V2nmRMYE}iWZ@AV-T?v0q7Iq z53maYMs;4ej{VZencY&F+S~vvcR=oo&Sr>8-bwIOx!&xq%{81m{Ch z8A^Gn+>V13^J z^|(?47mx3QTzg@S_JSovsqOpsc>NbI#d(^Sp+W71q6WoI5W9xZ%9ZzqTCL#$dtmC( zy|(6f4WrP=T0GHDltaYG-xbfZ8+I$dN5mS47BV1l_lhhRI}3jVEfNq;&xT+wF6{6f z9^P5s%AgW>|Lka!La`~++d;K&bXIs(2UQgcJ(`2cn(Jb|z8%%%xpLvPFG*jW=O@;9 zlvGX2YUJ0U-5r?TQc+B>RH*pNlF z+#+Mo_ooLca^rNsQBPEC*v?gpCmGR`v3L?h~m4kHqH6LsD#972H(trQv6x zhT4+D72?AvxEnu+ta<58D%uJW30y363H6VhH1l^k>5o5H)TYBfIusHVj|nfQZyAHD z$=@wr$z$;*ZMx*%)0B@9i&N|YChlcD6y-`0CxYU2 z9TpJ#E19PI^b?mdYE;=Au~#dHx?(0V;W|=edHSIJaYtDtvOn~CUPjt(c$4axKK83$)ImL05>)M5b^ zR@5KL%4CyII%q!*jDa)>+DT~~V{THAxYv3G3RF6?g()@A?ZA1mx!harNyclP4pJY! zv)%e=hvs5$)7P|YtFt12tNc^Ar&H=NWG<_Vmqz;^!M}x61nCD4UwHS|NpI4;cHVB& zmL)Z-je$i|o90_@Xh0t~#%|pY)_MOd=ETZc2y4!YPx`Wvse=NRwB92r0NumGX=7HC z@zsgVq4h3c{@6H7)Aft!FPWqi3LUMnqeIMho|$hT*NEbZ0KS!YvPF_pVgWCW-x~oo zsBWA%9qFBg57Yz(=@!WAg#eb|h2KIC8Xd9QlJ$~4;;;F5g5QBim@)2j+#F4uiG+&) zBUbDH!_#OOzD*rQY3W$&)$(c16le%IA2PT>wFzXU!oT8IU*R>^-F9y*9Ay# z9&K1;>8s+GAN*U-^^E&;{y;8vTG?2jm~TJAHmel*C#=o{nvAi=SkDS9 zg&JjVbEhJFZ~r6xw`a$nen9HmA+}GxJ|`zYAJfUGlaO{|$z-U;aMZ)-|8Q6s`;O1` zIHkpt509@mRP)@t;k`LM1Wn;L%%S6}*&3)~DT4qc{I0Vy_T4PF@FmHk(W$whxk{1uV6W5qHV;F_ z%(kGlab7VXvo2eb!K0-u*n67(*+t0^_rn)Ey{-`ZaVlsHDz|*7-pcvyO=!_F=oYpG z3ad>rcu=+yea!jGsTn%F^Zh)3fuER)YU zhiwQY`MnSp(oEyzqD1o8Ktf9W<3~E=uG_Vzl~!Astsuys)(1ylH?_Vr*{n$tBQZByD?hSe#n>e0v}nkof2c%&&~|sxhWFT zyef=`_)*zSuBd{}J)D~3kYhLkbAXRdFfW6fhtceOr^kZM+Vn%^5bUetgU*@i0aB&a zU7KjC)=yCT4TBQ6GmDZwNBGUTeczo|BQ2?oohaOX;($_9t0FF75j!@BxTz4e4Uh+r z+Rx8_eVNo<^dN0)Qd~ZhPO%>xO_i5h<9nDI?c8wKDZ6?|yFquK8GzK8i*ZV9EcAw{2QIPyvOcsjR%}oziab$g6nbr8lYGcM`WxV_kDTZ( zeN3m>_zmyHVu}1=ay9vdT|ae=^`ag~uYBYkNj|L*U6g{i-&gG>0r0EW#H+5EHe>xNNrVOUMF2LuLNdnvL z3g4`?7BuDYG}@+h--Z29-VfNc`HJt~F?>H4_jE;;s%(y&KEX}%E9~vy86@y~ZDUw; zDhhIHv?(>swqh*e#98lhE~<#X!}{%Wp7bJ@x+SWdQEx+QHu<3`0xt@{FirQ^#D?L1V{6Cb{+iXlkVVM+D#p zs0ZrQ&poA}+(Ni38;h^a0TS za_T=gZFjeBa{3ehw}^?4CHC!)jb*dr{sgK7#lDLKX>INI^J+C+#@p#2&*Sn^7u%^W zll{o$W7;-Zm<<7MbcVMzzwudb>nnlsW5v{XDa znnyv^h_0&n&16C#$4~19zQR6(?phMRf%OLxGSR-3jI(d1f5%TQ4;T?#!~<*UD`Ag(4^lG8^&Aw!K*b+}#-%Ev@Ue z8i0hot;8>Shr~NfXVFXcGh4V<+Sc?HnVA68E)R3(=%g5w93EkRG|s{4kGG%Of+_`7 z&l5q7z>%(m(F-9p+XW{k!wpy310yHhogE2Zd=rlidS}uHwrzukNpdt-HQSd+R;v{S zS<4p^W9-9T@H9T1S^`?=u+2MB0Ne(BSP0bCDt|9(M}~QDG2r=r3PJb~n|{Uub=fZE zh5u9`vn>_+OaXfIdRY5_3Lf9v(D)F^0e=P|u8uMz?Os1jRLqwsYuqQ+%I&G3$rH-i zJ1}h5V;NXxUkO{cXk7b)ArbrDJg}rGnC%45gS^)8@wn@n{>br3z~_G$eQ%}&2uYE+ zAs=LO0tG)`2rPfs{JEIp^r!7_uY`cvzDy3U#zzw0KdV7SaFM)@O+9tM{&0Y-x@RL$ znj4Xt69sCs)-G7VXnHK?1>-VCtLn{aM$5w+R@M~XN_h?jMI!eg3)G2yzFxhVvBw5H z>#JL~fEp?#wp*!n?=9k;L*iJ?@$P$$$cvJ1^NLraS}wi@ClYYzd8*OF^>D$6#Cm+9 zg{$yeVd!)M`Yfy2BX(O_iIHAx4xhMj9o=P@1rjoT=*qhUg3_UjJQ*6V)GCx)Z^Hbs z9}jHxOwJpc0}G7$k1se26S#ibAaD4bA|MF7c%nPEZoJK zxgd_I1Uxl8MtjzsKER1#G_Q}M+SlQM7iy;0n4VsF_2`UV?ls3e@PV4Fh+_Yi1iJiM7lMBCCvZ*<9X5ne zhArMAfKx-a5w08gPp3b=_^Et9!ZCsPqV{sGJZlWN*-D;yru;3z+!*-aI`I1wX%XJg z2t`Q4aIxQ)Y+-I69wk0JdA|Sl$5eE)$+>tNIMDZ&tWm>-Q_P}5k5FX}^wB$f%*ul%9X+i`B-8G6A6_ESZL@RmRXJdWCp9biaJwIU{Krg^eu>Z^DcK^Q&=TxCUg3ZSUOSYSw57nIgE_sWj zO#5cTd~+?Pu9z4Uf$!^;ubY4*CdKDooq%#w>n3M|i#DWP(0Cslf`$cHfpeHGqflNI z?paQ$J?QJ)m6D2cEr*&CM8({D)Ekxe!RtaSjYlF^K}iXv-I~zLhtog-;B~10*zH#U z?4v{76Fw8Itvb2wT-Li?Qo>}WkYfqC|DFOk_t3^EG|8BOxl9YxZ@1!?U4-qV7v2wv z;H&t<_9qZ+bLp$_J$(Wk z7b)349)baG@)Q7no)CBI6T6qmVS$Us5jx;b|18A-b(no67FWy5sA&f0LTapzQ7ZE9 z=IBUIIA(`7C2Qs44-vS`uK^#+n(ZW=&^FSXD8!?%BSnS@{4C4p&{KUFQp8q$Y#ZmuP!&!!ag=N&qM^5XDbZ$7b=DB* zD8f0hO%1+BNW{}4lyej`dC`{Ov4N*fwn7))=Y}^1a5%ZDJ_1R;ho^9Z2-Z%wRs?#b^ z0lGR7`JC9x^NgyStk4ouQ-U%w4bxR@Rmy_)(hS#7-?94FW<;2%lO3Y3yU|dUZL@<> zcd&$1`uBAD@M@+Nlgs zntc%P`zFui2OB`bB_XCT!IkAP%xZuH8$p%E1T%3oKgXKou^$%k&BSrC!^p+o_~v}# ze0QGp=5@2w16M*z?=9PRa_>0Uw4no;q1{bUf%3{!sNYrYC{sWV5;27$$$(-2% z?^vC|d69PTk9Hmsw|qxmCm3thwrs7_Atb4Br(o~x6Hhme~5xK6Ur_qOYt{ z7#OGjIGbM?lq>{8?rnMsC{E*PL=*Q~4a>tS3+G;Vb_=7}3dwod0R^OGSV&zqos#1s zrCpXM~^885iuj!tpah69{) ze498c#9i~BVf`Iv-~69(=FlrTu{$Q6iV)iz)9r-1AC^fw`fm4b0WGWaw7EuSp-;<-mah>037Z%*DJr z&8)1ZaM2?)!nvJ50)R{(=1bzf-ti-;-U$Hb>|q^7g1{TRTdqbz6eQ04j$%scD`=!M zf~)%0yhO1Rr4Mm+JS%lYT(P+0`IZ#O1RBB_o+8hpqdfpTyi8^9ZPiUF#M%Pn>aY z+V?(EYN8B+868`Q<%9>zesL4 zL9?qjLYVr>+-BN@AUzWG9Eno?q%h>zc0d7sBbEP+9&g(hkms>Zvx+)V$Vx0rteX9$ zM?|p}B!b2mh(VL=uIw7<@&pp=+AT-1P5Q%9AS+8$vy0T*`2}d+S#H3T4aXmih8i3C4*_|chR}nx7W2G*CIpIrbPmM z+?iCR^PieMa#>+@gm;%r(y=u>T5vi;*aO2Sd1^v!d9UH4(d>{~voQ{|hkCX}!m;yb zBsED|vkcmZ8Q8zRURQ*%KdK`y!Lt?V>OdAKTC(+bF%GsUiY>fa$&caSm8q^E>E{3r zBNwR8k2nS)zLw-EPyPVKAtRm!ZN`=b_~<__FR7O|(o+mzCSU8MAcd&l-{G|lL$2`} zK<12;DGM%ye`!;Kk3}y4f)z+nTMi$Zzp&!?XBuCj$PVz*|0AlK$q{cF{~0blngLGL zDwX;KzaokvV<#eYH*HK!#5UO3%kc@5h9vgS=7nED66*C7wcGa2Q4OR}q^B&qf~sVt zV8L;(VL!jxSA#Xt41EVLm4;*5rZpitJWxo;BEX<8Eg9tA>u!`t5;F=Jh88WRdRk*N z`7)Tc&)>ZVGEHs@jb|RbT?2g3tZf8t{NdC=zwbnx2V%**hhbwh3GQ zj8a!g+NTwksd*`E6IxuT&wiRfW2q zjjU~cg_^la!g5sNR%9}3;c61zXMxLJr6;X3C)bGeS}#KRR?;R{)H>5EH95ubOB-y!|(Cg#5? z{3@6(N%0{6-_rzXtNtw>v8)$5KJnyzUMYElUoM8TL>-Wu-mQ`LhONC%TSJ3e_^}{Q zj&FVgNl|QCjb1{`Y3uGwv1G{p3DJ5YZ~Qj|Vp4?KP15(e5~_kV57p~SDH~#x1P29y zSDzFZ4qFB_yU^*F92{n3E!iv5elL@*3d9)6k1?r$f@3&nFB+NXD1iArPn6zrX+%&F zJ%PE6+P9h^&XlP1JMq!p-7L$Scu+aRH;>*OF{;C4OA%3+!DT3}XnU<)EwBbbZ2oOB zdmS<6=2;iWo2s4rEteNd_{*8?lkEz>sF)y5aF`=iLqvJBe({{~&9LoGmUC3fD6{Gn z)MbqewYTjQQanDfI}*j7=f~v2nK=YrQs@9;6SfyZxDHS%Z^*7a4|(=k!tdecG4rMX z|6^8BrURFLQV2|!g^B~|PX`ZeWUQ{_G3j?`lObd>uSRoO^HI)25l}3|RL*U%_v-$< z-42q>xnTN^>^RjhT`>Q7MJN$(|8+%b|L2P6Bz`-AvB}Xe(LhY9pI2gQ6nT1sJh?<*!oztA~X);mjG16bOqJhlmgCprke-> zhfC&H8k%lwGB!vPAt)>Cu%Y(OzPO~8$^ho!tNJh0C!7%5NjSJ)H-YbB3)oO1w;98^ zCfq}?-PQ{J23obTObkYB{d%QEEWUMMvbM=>Iz*x0A~FOUJ`-O}d<-&PpvoqFO!U8! zED7VOC;&$_BxoZRL5V6)QvDsHr}N565!O`m^@ENat_}Yd3DaHDwpEJzo_0hSf&C@) zRNN8HdV*;1HZxCpShv0_uJEaiGxC#44i_@2`-V%c?r{A3mqw3dIWI4NKVFmt#E#E- zT)S1@Vu+tW@v%X;nIj;wOfvCe;ekSMmNPt4@$b*SnvW#rl_<}c5w{eBGD(sh&N-Lh zlMV*iF}|JyV>50QkCSx1ZG?H4TvzSYmHyvf;;&@&uP>ob0EWz2TSrH5*fiV>!`m5C zYiqhl_N(k0+fdwb{-Um9MxVSE&m=x#pEV@tVKI)0dPETm6oUAXmWmgDMt+UBa@)&M zlT}ucCNgqj8mkogg4kpZInct(4AYFgoy%5mpP78Cr+l0mfI9Clx6L;~$Dn}^J7Tls3~iG(WMKdN2KN4lGEwidBzmF# zV}VVpp^bgGp5jWupQN6ZwHY-Wm2ogB0!N^>qu0ken*jGK6aUWVXWhl04TAInXp3Cc z6;jsY`p=9$Wlgt5e`H-_vc3U}H~D4rlPT5+YQ7%EcXv!2)jQPojjl(uorOBhOe&C1 zB)t#zTX>+OogDMJwi#1dxym2&pwQDP?HW5BdYR}j$6*|V0XHVav zr*nsW*j45W4Aaht9(`j%U`NNGahSGsLoKIKTHt!*+G0(-4O{snx?->hEl{Cic9>%h zX_GP}0{H9sSjl0Vn4A4ataMp?o^4XC4sj3SZZMrv1wMYO+H9z#k2aEgR1EJDPO3Jk3SSxb-eLGjBwLF(ZiS_8IK{)ym18O{Vzx&15!D;fFU6 zZl%$3Nfw{S=`b%QB~60Q@~C#aMee>Mj@`I&yGE?q0A$t4)@nqlwPBz zwJ>3(p7*d>&74~JjO6pEJ%m{n#+TH!=GW_moRkvMnL;+H#e(LC#ajvS0 z8fd7yiK(LF^v0u&MpYXeyOGu_1>$2xLTs4%W_*@ig|8~+elb$ch^RedSo@O$%;l@5 zvb79YQ@`%smO*@T{{f=-{tco${|TaYvptuXVg*BqLgSrOcQL@ipnNqA>9BHhCF^XILs0_j~c>D1{Zu=Z1S(#-t z(Eb-PrmUI|s58><7m)==(s~CYeddXGzEQ=Yki3tr4;7S=Q97?!aY8pR!X%6Zl zo{;;!r96zTd{e(xP2mTmJ+Xc6jJNoFxZk)uiQq1dJsgSHtBHI>TBWkbQHyx(Ynv4u#*8gkm<_I@S%6S(B2eX(Ktxq zg;K*H)6VNP$Yto2>Ct8Z@rO<@MxSOKo3Tf!8wT*jG*X*jW#J!CRR_F>3lAJ20~^Sih|Cxws88VzFJ1eN*TAM+ zn94M0@AC-6islPZNaIQ5n|LRAY=Lt9mc?lD+j=s#RQwBxw)-1SVwtkqOR0dp>LUD<9m6GRNMQCsx)NbNw zN*5Y2w8$BLM;Z2672bpw81r(2%snbgG8uieo^X7gFH zC~RhM34G_I05=Idd&uD!{7NFin=-1&uqZ#}zGOtu7QlYxC&W}v9U(;w0J6Do1Blrp zK~pRIKIS=H_!8`9YM$Z|LO7Y}*VU05#v5{rDh<6HbAj5*usWx2b+(xvRx{KeYa>*8pQ=~yMHj&DZjoPI5u*t% z#VOyLS1?a&8()|0gFn z@PP+G&Sd zZw9?O5)S@O%?|0&zJaU%%F*oubCdAwYkIpp!d_8{>1 ztn-H#mExRsV7T~Vd;9aibl)OWp?|O`nm=iJbW|0mkv*BBa}db;VDMK;PZj^VBY;5pxd|; z!XZD-g%t=}h4dm5tIoD(W@OvJPpg&jRGw6}PJ(Enw`Z16Zs51+#1Q2aqG;+nd|k{@ z!h*U3SNlEJ=W@u}4aK~A9L{l8{Fk$f$E+6S|EM?a|Cg3f`6n&GK2fOsG1lT3n=t*s zlcTS0i?9#nB#qzux!JOkz)}f;7CfqCk!(k@^)s^?&H2}6ftoiWiC-M-IOCV2w>M07 zw>ys-703nP=DEeh_H&qRmJ%~P4836lsau36C+Mf)KFfs7Z?VIcLw=knLT%=rE` zwtI-TjjaDl0tv;hjxfH=`Mh%T78WF}9vQJSF>P2WPdufjHt|M+{Um+aU1NlNcO9MX z^vwD(@Ax#R8@jUbyDQi$>~P=+FTv+~*lX;1iL|9|Z_i{`R$sPjTjgWf)X-NnSpqi( zf|WW9kY|j@A5d++qF2+no(DXE#3li7yNmZ~x(72HIVTKacr7$QPg<-~tl>R8l<)`9 z4ppwe*K_D$6`WbM9*Min6S<-6u2^8=j|}-xUk(d>>9+!jg_muc}f<{~zGPlZ(P z@Ygy2%-23}aeK|&gR8QaqLg~GIHp@tk5s1I8tdy~uFS(6O1K}sJa65-gL~}MS7aQ; zk}oQ$H-Tc{%OjlhxK@;|lj+ZD!c|tWXzLzw&ENDJzv?pD>uy`hZP zN16-I1&O$b9-KPkxmG2TWix1EG{OC4$F%rc4%H$bH9tXe(6f5-cF8uo*Z1>2eSC@U z>o9%Isfeka4PR|Ac>Z60qJNd%;-(t%rAhZ+|NR@6bNIk zAcW=X^m&872x9VWN!4v_EqLCaU3ViIA~bsNW#|V8&RXo)bSZx`Y~yftG{pW5X#nMi zX;yt6n9#04U)USd9uJyX9~wC&WdH193JLGV9Q3Nbw*6W)wLF;0c7~e6V>b@eY8|Ki zFR0@|T^o-$r*Z7tjJLu7>Eer====kQL1ZG&#Anf#rSw3)8#}XjzjB zJZkRoYF3SBsDQ4BG~J%}!P+hrFLf&U46pkK-U=;8b*g?aHK1MXqJL0GPVZfc@OUO@ z(A8FGYNK>#NBk(6HYALXOfCje@s&-oXoc7ff~WZ&DT{pznojc~W#v@;{gDZe?Umhe z2eB5HTvsPDCsZfIRn5^@n3KcT3EX2vwztPf>&Xn)TeS9W3~QK*Cbt+bG>>IRIBWWb zWjB~_%@^W3;YoN`?33u&)BG^)`*!Jc2N0I`?!ws&R+S{}jePQa=5xcN^#8@H{r|jk zq!aZey|df?8#Pf+t&2HO0afK0Y~pW27Z#S)qYo!eSjTPd!6drnZf8um6mMo~aZu68 zVQlDIMIclCei&T8f>q`*7n}_S*#2K-Kda&GjeBHUTT#ry(03NzVRp)ZoWx(8zqy}F z(R!Ozh>RphdLm^(Yo_$Fr}& zN`B~eLG5t{Cy7SkunDPv2A&(gZ(s}{?&hLrI}Zssu-Hb5^d%SO{)>Qhw%*Bu+UwSX z-Z)R;^hFu4PLsYytzyiVshre9t1IoZXAx?v1|~A-FJi;ObCyZ&`#-|+p@RI|l4cXm zKC`gR{ps&xGa;^z#=}C2{FJ6=bxqA=mN2fVYS&fV^u%V6AF6_a(fhC{@9b2Fp#TGi zzDjSf^Nndi?d{IB0YqO`rrn58>dyC;{5;K_u}G$(b^cafmFs6I`K$Nh<%7$Us~HbQ zsn6Cwf7Y+8!`fECVcnjE9I(=$!WHdgY=jydR=HwORhX&A{CHlq1D$*|gM*fTzgbUf zoI;Q4;Xw;&jK8y&!{Y{_v6Z)F=sX&J3|stTw2YMHw-z8i|Gh=0#|Ha89RL%2s`+~r zPzto`)KMRlB{lA|#NH_8sd?{KM{V8aj1`G3+>loiF!W)pGygjI)eR@7LJPT-zi)zh zhw1H?1EgW^@T{wy7#6OTnhEtgWMF3SG(3dGO=N_zoBr_XNEMxI$yI<4TBqh*dG&!z8c>F@L^{2ocl|?^8>vtzUXE{_ zZgOT)nUkwr)~he?6|n-cnGiAzmWcUr^@~)Z*JWi>p|wI<#`Kp@6~sNkJIThHdVY@k zQGW+hfs!q6+E94Yb!$&6oHp`1d;%x?(pTf%AJs=rU4#pFxb>5^5>DgLUXFk4>qZ+U zEvp2-t=(^UgIf*!2?>_{TJE7Y)FUgB`T?s}GYc#CXdBXupOGBhn0 zjKz*MP^K!D+L1-_sf)RnJa|0@iI%xz{HjGH;@b?*@R5B(p-o^rF8AjLm^xi~qHs7- zfoqq@(r4@NslMu!i^?}!mUP}W+(?Huf!2Q}vDa>J)_&Tdp*({hAmfC4Iz*~aW!K*F zt$7{l1Fp}$u&=Ynxnap3_b^(WJq%r8sQE<3vsy;~}F!9lt?~yokn0tl{exn?aEGOW{MFe(Uxz{MFL?%T8Yw6SxY- z$RjWq+hbJia>CRSq*@jgU=PAXcJ^Fc`UyO-4z93G!Qkb{;AG;c$RrjJ0f;8(sq?6y^dBpn zk4x~SU9$PP?Be+5B;egdUt<7WQhUFp)YjL6o0J!RAayii4UZWP?>rtX8lbU0RiMTT z3snh)B{Mhatkl1tC@qi1tmI|5Q#*GgU-VkE+0kHPxM+=RfJy~ntLrp0^vlIdl?D(heZTvkzZs&NoEb?y$)_oV*G)W zQ_RY=1XAv`Scp|2JJmU8JC~}&R0l@Bcp?&Z_}w`U6z5tCpBT%vN4!*z8;B=y69mvr zg7lS(hiHDk;D~l@ht97O$;CPsHlt!x&6cU8!ouw7V9UvT4L_LObtLLW?Sm@TkFjMU zDkRTlnhuf@$$=^)7jdyls1Ltn?dLdbDQc)aPIo{{eR)vF$cp#*?UZHA|FS1 zGscVSGJmEN+{1>^J6DF2h@)9_;6DYN!!;}>meR+diC%)4x7*XjB zogpY^bVP^_N43L!6VO^y4|E=q7th;8qfR(bIGJQlK=y|#CkjjGge0p7Vs8WauK!u)fLGZMa7**^abdZJY%Sk#-{WH)28`gvt!(ot(qubH?F zfwI7b6XB|>jXJ1c&40(*FHvH0Vjk^C?sb3_JLh@(0Y%#8b#KM91W98BoQt zJS|`M{h;2;lC##>)A)h?*H619G!C((3xmAO!lVC{ZU3O>%v8y=y^J;(drc1h*=dij zNXH~hZ&6Z;_aX=yHUDOR{IyWcTKFq?;x}vpF4s}-f?BF@l^|R$y8{hIUbvOZ5E2W! zc5M7bEB)Gb^GCk0@cA~f#G`VSSK?%oPWP`NgsoWZ<8EgQrflcW{eo=`LRSTGV~26F z;-E;$(Ykrk_q1tw&FeOKQC_moLgjJJoME~O1?B8Ma*+XU@KQPM2UG?epH4Su() zYd{sn3=pdK4XVqV5T-zv`-v*rK65lfg*{V|buEHV63X0`qQkLHTv}A@$S=@Z(JWve zvI_2FbxPPc!SjFu2H40IB{u?Uj=5#xe}DRbch}f_5_M>VVpszBE~X}60<_05da=%$ zmu6}vkgr>}>LNdZunocpYdMBpf2$H6&soOK|L5Ng~S|#gL znhkvW_DqBY2l1?enF{PA42K4}LhZ&R-OX3x>$(Rj7)N1>4i3qtlappijFsmYC`$Gc zG81F3-YpddIM09adBXUl{1$heg=F!w9h%*E4iT$!O;Tj?*9b%De4oWK+Ep^vso!n( zKxxe%q7Us0d_{Q8?00aUt4LJqG1CO#C54q9CCO~A#YT;a;s;ArNWtHr*>G%KnnHqS zXKg+E-+0^)8Y%N*N(%Rv0Bht!7h}xZ$k<&&?`jRtDI+ueCem_Rb!*|DVV{q9g*Xd@ z925OvEl}eu*)J9@n4Yq-LIQjS3nuVY<~&6}Vc?QFxfPN!?$Q1)DH&T6yT-CXB#6hn zuma$U^h?4@N*3hx)SW^!mr@_SDcFG{)Ow-vv?d%nDr=m0zsEg=27d+J&xCkp+iRLV zR92yUbnXV*mQ)2KOIlg*xOe@q4Fs{ugX;W8o@q*I#Yn|*QH3z5B3$pGAFXDB#3N+V zV?dD%3jqewSH~E0!7qDTQO_7#Q7DQw29h=OR0nsngdqnS76e;m0NM0hIBVNIG~+-2LvW-hJG$kZC4FV9g56VY#BW3;~BC;T?>A%p<8;6XHx+#!3@OQg_C&fz&O z-f8l}+g8Aqwe@SrTR{K8RuymKfWr#^v6LuQmYdk1i1_6eroGmh6ZbzvJd}TRVO{>+ z7tf#km_fC`?BlxfKfTv#GyX+W>#BNIr6_6xB6T?wWiYqJ%r#n*5xyQ_85!cfL15EMm3ciKT8bxhf6;ekb?el;lEDhNJ*_t4HsQ5X zA)7}7g$0h%5f-ajf3<{~V<&4CIe@DwTzj#;c+KyxGvX!W=6mPWVRec<{_JMLBi}EI zY-$Oe9ZJR|G@9hZ_Tx*bN0Gt1nUHLHZApv*?8 zuF>tRkmX1bkVce^55-FaKUyr(XcL1hbz0)^=a_1(|Ld9P5%?p4VUr$J9sLY)z0~O%dWmw0_PeA|- z5G_g<1?>>GQXR|vw`BU-(*8fj-od->w%r6;NhwWKRWv?uR#?Uo z$jImjtS(pe%#Cl2IO`J}F6uW7bsg8rq)>>+oRz%|-p_Ek>vX(M7aZ*H-Fx#jwe`ye zlTwxE*71LuKN0K`TmAomWb-9ZE$%FfFW1U^8pk-NZ&ZhlT}Ok9)%g=lQ18B~DjCsa z%sSCfM_lxGJqW(|i8Qh)%I*v3JSFy4e<9#yxSM4_Ec$yfuDBVM66se~{L4ApWO!`~ z5t439O4i%n6KW+C25QsM-AXnrwt%#3C3B+@6JpCnrODO;T60Y}fUm`5?tF(RHDU~c zZ48?L1KJQyK@*e)ftBcFLZ=u3Al?&k0S{NQXg6uOAlh=C$%b>ur}*U*syuj%2mW?2`Ko|@15F5cqCfHVq=d(ApdSw*jXuzBrzEYHbC7*BxfX`eQ#qkRg`yo zcOk=GonxL%Lps^Qm@#|lNH@?Fib+@OSD0HXl%A2hHmOSk z?ML+Bx5g3Z!dQ*V#WUJd5x>jF>H7H5Y`1K{Z1np5>(5KK*|yGsD8CMbj@CuPl{Nqp z@4k0Ab)q&nVgK>`R=)!T%R}c94sUy zdY}?JLo2LG=)J#9mGB|wckuJKJc(Dhd~Fuy&j?q)^j+w{VjgOYb_2ga!5X>8-o1Wu zCThhPkh|Lq#e=#z*a`;onbI5l=>oCNu0x>Ymxr(-at#iKa zg|T*@54<)-OH4Wl=E1lo@u=TmMb{IA?wtUtwJKqWv~<|Xca{)t^7bV~bpZcY*}IQ# z*=0emDEcbSqhblNFHo%hF^a9SWgibJnmc4crjB#q@+sW+>kZ2{2FOPfxoLM)!gGs0 z4g;#Pqf%5HnBlk4aw_{x0ZyPV2QHu^lpP~+bbdQK`xWTu_v!m;U{ldWOih005L^k{ z_8YG);WQM%U`IrvcDK$u`}wLHku$*^ioPb5z^tFYA4p@E?R zlj4BMsMrn|5ikwC%w>34b)S^03OH&r@|C1|x%2A2%2OIb{;B39Le82(Tw{7c(M5=P zX-{VK1^j?ovV<#Rd-K3w$>*vxz=wJmEPg&h!ROrMwN_Q~pGNkBku`S~ubO#}COR%8 z_>kapP`7hVyHAo{d?#KZ8B5rD7$ypF>S%a;kE>(R6yV}q5yI!91EZX#8H!io-5iGZ z9i&Z)$xcwPx9EbfmxvcV3y$>HhnEP-9~ z7BuFO+d-yV>B~%!g2vH;fnUcfLRl&wRDv;7bAA_MBZPdA&4o{m0xu7diy)o`U%=H% zX2>KhOcz2!Rz{FD?XF}$rXs3Q6y{{kN~gxoODJA<3!%B|B2isksc`@9wd&5v)r(R0 zt(twFm>eua7AL-5r2)|LG45eeb8+HTYaDZr61gzIyS#Z5@~iJFT`*Y`oI8s#!)a*> zUzz>N*0u)IRgDSNtqs#bkePA7>VX+5>IiNuDPv1$6+&o6m*KL>u3P|?vaK#Bru@dU`Zb+)zgvLwpkxydU>@4)xqkDw|_?S z@6&Rpoga1qBBeSyA*Ia*yi#f z!_~M+_3!fJAE3%QpZUm7x}_DZ*kOj*Gw7JkUQe_D&)=GN7bc=rV13M6n-e%wxkUF~ z=44GBC}rw7F}(A=4~XwBsfa$(7YNw3wFUz}){y&8-J0)pD{gba8aBED;fwIYN%)}+ zyI}y7HRtIwvu0H~f&iG6-GyrDxxL`FcQX9B2O($P9R7*L7yHuwaCf!P4|-HzbS z#^0BP>{jkG4mYvFsc}6&TH`k^`d)WljQcmxXUEhqFYdPt9J(zwdZ+5KOeeFVZLvEl zNiRzksXBlApyp;@v*L> zU42!w>F+F>5J!S{%?Yv8Mj(8W`^d=K;QmV`gH|F4a3oKCy0tRiV6&`({Ju%c7Hg0;x{#hZQq zj!P9Jw6F)2e_iG34rLQ`>%qK{(GSvu*L(m+T6@tXUjPeThT;tGeSywhaL6truz1V0 zCKvGJ^t|xldDmxz%@tX-cUKsrCr4+)D3Im*Md0bDPXa5@aId$!$5Jilt*};B+(P76 zlNqwp^$aHGtdK@M@q#67g{Qi!-+z=y*%8iCk5tBDrKyo|djVInGIqNDNMpNJ#XDi3 z2+?-CMY|HvYzoUY{wXc3v!BOHp?3=zGe>wCj)@23GvWIuTFshSLfGY++rj)lSM6Ta zj&;DmHZapc&#{l%?%;2Ju^`9c$f2|`L0aj|(f-`8{|h5j~JqP6+YXVKoUOQ+;-K#SBSD%^j)GK9I3jgkE!Q8oESD2yDn zIUXoj!D98L0yApJvs{j`oTeG8KQc^ag?_d`NU@;??g775aN^lEf!oM-^v_`p#NNeD zb(T3XZ}*`vgq0En=C_@F734l&2;{yI$(Y`{rnLZhABEmY4oo3aq+dvQpOwM z`$sZOchRqcc`B3n;4SW}ojJ!XjIIH}qx-=nbVI;1(se8(pBri@!78o^NH<`c6hN9$ zIEqj)pB0q}w<~FWdhI!+og8!>9#}+KqJH1o%xtq8O1;Z752Ke9`4 z-Kep)Zjih4&6mzu{ud1X=>4A&?7Z0SKsu(2IT+bVYiX$r!47B$`?Xdmt8YsvSo}Y+ zA7x=2VfKJ6_a|L7#$o9q|7c`HHH;utoGuR4xk-dKObEeYob{;?>j>NyhrxvN;5z!nuG7cLDQwg%?lVK<@|_HAn@df!Rz_IiJ2t`CY;({4=HN+Lr80JcjG(BQ zF8CHYay$EGpU=Lld{#|oJz&l*o$bL}x|t%4uNBMw2RVDPkG6m|kCi9iOF4x^5J4^O z=UAJ5lP=q9jMF!s49Ce6CXEANLmhE8)Uj&2!Pi0MLE$gC$DEN+bE>*^>b$Glj`SEI zzwPNXhstf=4OK|)1O3LXER?r=7$0X1M`-9&D;g$13iQ3#UnzH+0s|N{D95#ypX^KJ zR`o8FDrr)$_qvb4M>R~cSx0(b*>SJ!LjET*8?TKH9>-{)gPtD4v>3mv0H(5_RCCrJ z*|*$AJ92<0vbxi<1KfdDgkfLxQ}iM{i}Y2L{Cvd zPU43GVz*$mvIS{0e)Do8l|`FCe#+rEmu51?V3YEtNNV%~+L%PLZz|P{SZYrq$sfDE zQ)Y)a`xxJ_+x2m|cp`@tYQNMf%eT1<;D`@dw77f^=b#px)z!ZuE53d#V7N*M2_nHk z<>gO)#vNJUb5ToEEJJW45h__FBEQFA!x^F?qa2Ai;^Bc($1kX>UI-= z6-x-BOUJPHs(t$0g{1O*6x0Y(9T`CYL=<%OeBB6#G{zoWhYUe_Q$At$yg0KDzW@)* zg5ee%SDX@!^af9gIU-xdBmI%G*QAw(9*LG@gkYfS)ht4RijSg;1n!CX^X{JNX6iR$ z;zTc9CT5IsMUPj+)n3sSe{HTEG_|2bWLDMU9qM62$R9iu9dX|#-%k!2*g)d)$_2~c z80(op10)V8*5n$a{hYbl@eER2xn)xMo>L|jvr|4^r&e&xxg%Pcj@KCBD?)ky_LgFQmZBxt0%z`L7? zYBjX?BIq|jnR$%hinVb(Bk-hVr|(8`bJ|?PFvwX+e4)mtBwoc46C44xg~Ld0Sr$j& z)sj4Ej%Hs%0~5%0JeTIBuOI~{gNu4mQ$Jayei+oW>venN1LtVfINCuRm{mPHW>I6j z-8QkvMd?9P?B|d z*Zv^-wbZ(HZeU~Wa5K(DCzmat7tjtGk70uDt^8(VskxON)=>_1k;I}yd5*%V5{#7C zx@Y5`nbw(}ae}G{!(O^P@ent^xD;5#^AH>V%z-@)PijZXRwWS#&4@oAXd~)~DT_W1 zyFat3KAR&5qB00C%YMe!D$v^+AAXnh0(x;Hp6s#WC9oO^=Gj_k$o;^~o;CJxWv}=d z*2(`7%0T{oT2m?>69u@OG#Sw;?j0_Z{w@5LN~n8~x_Ry**Sv}??#wbcdsAiAtxmqn z-8vC$q|UxS6?S_AX7S5;5#ywvtUcZq90iM7d##UiAW2v6u zTQM@NKv;yIyu?d_pqR>?87_)b5YjKQV{krbJmb6X$|QabFud*kNfn&``n%3ESsp?0 z>oX)h@mrS2|2M4d%qjoe$WK0gZ2-X=wxPRb##I{1!TZa_Mq~cjy<*sc+q#E2-NFPL zO06Lwg+y%AKo@Ryp-)7gEn%=^rx&D{!j=>ap`Fwf+gzh|5z-}8ixwnGyc0HwE;%xt zz6V0%+o19M#)im`6}q2%i;q`SsU9O7nk_Z>TbhXPZ%utHS1lZi{Sqc~$|d1(A&w)> zqW8KsyER)Z2z-xlm>Q8uq!w_(Uh+kN$zCf4paC&pc4cVYrNu=Kg+}f4u6iSCLSZ zLkOFh=ZsmLJ{9@hJ-YURBYUm#HJ;UxWwS)a$h;%!h*e{x@ zdTD9C8j)poHUP9bUqr}eJ>n2f1VnMjVDs1kB1fIFEN2&(%c^Zs@p|Je;c6yE{&dhO(LmqyQF zkC%m8vrDq|ZEmYN^O=m5pEY*9;kH`smr+*ZhRNR&anIrm9XUf~g{)nY409!gg$-V_ z(-+^`wP|m>W|cF$=7|t)xCiF70h8M37mX{nDhs(NCV%oA1*^9>-IR4Wx_iZXajGCHS*RoWQuV&{T_rbP|G@bLCvf_HhK_2c! zPK=BAa}O)EL;^gKY4z@4&l+l4r2t?8a^GPJXAd@H#Cm!-VOU0tLd3~tg;r3~!fohT za7-+N3uF^tjHpc}^W*x(A5G+Px(>pWdZLK3A^k+o7K!c;BN%se-LMC+LF%lh^>QnE?&V#n&HmE{MqIS7Kh7>o)SnD5*S!- z(9=GD$Tefl03%tKSMyJjDo3}?mGjO~-sNaon!uz6=Df`g$+q_xFhS-Lww`~fNGtoP|MFx@#^y2p|yl7spA48s{; z0J*1_D2f8v_!cb1s1wxt&=o4XBn^!w1fl{PwVz`2{JwHXDPbBu*opO} zKvX|i2zFP5n^*IAR$(B80bz3utqD5YOPN9i>S5+s={YuZAy-gu#*Z2@TJcN!*n;i{ zv`X&6XJx^z+BhA^kqED8@xM7yhlSmV5lqLxWiOqtuJ$c}5PdJfts}PYLRh znhlRB!m6s{*VAhKatzDHy1e_h-?5zY3 zoVpTF)wEzL3iv@jFN^j!|sJ7&B)rq;2q?{iEhr|*6}tWYfcFxsLR;H2_7^Ez|~ z^J?$HWG)~ozev8O@u)?aD>U2QqUE zs>{`kj$O+hmJ50Jjl1sU6Hb|FAm4Gaj;*p}a-C3?nt-o{ZeXd3K?_PpHa7wU(NQE= z(?ieV(M~n)p7LwTFjKE!a?EE>K4i%?A-()%Nbmr9s2x1~BkrOiM2+_L#IG{(x)BFp zJk4Goq7IHCQQSM-Wkt9B!^rRfrJml7B5pu0Q~q7JOCJAGu0OvyaTJml=h8exZQd?@ zIUWL%A_`hF+K>i27w9Ei+|iX4hyq3Rze-?AXRjeortH)_1S`Z6L1$1Xm>5rXZMSJN z;pxpqU`i}PT@Qs5usF8=Lg5@do>SdvO-jkt`LK%JTm!$TGtc`dc%r6|z8P(9(b!qm z&$PcJQ_AaA;HAnT{?xkvu|1n~Q?kp3xd97jy zcylY?aY+UEUW(Bo$1RL}AIW!oA#ci7@fr|!U{@r27%&%fduPt0u2>vKbDSVru78{V zn}_5sQrnYcVR~7G-Su?wqg4CaLSf#n%K*fp%*D601`!###qT>`&aFZnl_0?prdSuo z$rg8>W=mFycT$G=$_PbTY)E+zqXTy!1kCI>Kt&X-s%-yXa~rL zVOD}J-9MNGaLxOQn`Em)CfvLFtgwL+ZGBbUo~^TwZU{%twDCM*ED&J02|3P!gN99` zT=owTcBBo{K@xrN-x!9C+O-Vo8W?lV~ytA0Cwv$wSS6Jt2Xx;pJaOeh64%H231 zxW$zDyjjibhXWzJu^r2q9e$v4rOT3sk!CAGoA zYUE$vSd50Ozlf~tiJvHg57p_{fAB2`7sm3Z{5AqWNi3sR9=5AFXz409W1AhmugBhWgdVS?2spEd1lIiaM;T0tRBtE> zn+hK&*hm*4U}O({S4CsprZE{o0&gEbt{2r4D?O3WU$UZ1b%*7>@1%#gdy=fnYwkT( zJ>GwCcUB>;nU>pl=>^tkOb9Pa9Qpcl+whp_bHg@P5=?n?<0t-B#N>BC4voR_hmbf8 zQ<=z)Xi53nyJ@k}&6Fh3;bcE2y;I#(LH2y#@#zUDq5HxgEntf#kHe3<6T^pG)#Z+l zgvXDWZrQvL^7%sFo%?zHvEjBa(jQ@MG;$#3w{O2$7dsYXpH&J%Pr+{iNlW)KzSue1 za61(>T+#b)!FSL&%i90nHm?6S`o6qff9~aj@1APj zf+D;5-gU|h5ZBW~G#gJVnW$*E$&i=#=J;nqf3lA{_|qk1ZX;Wru^-WHBM@$u#lp;;g4N`7oSyEXXTpBF}MGA8`8PXQppS`pJMa*|u_! zIoWBklFhW~y>;Chyj3PoKj)~@bz6Y;19Xz)IjzI;so8#sTOD*W-pOuJ>QHpGFx9DL z*kXk;b!!O4Vc_TcFQHdzQt5XE>EFX!$JR`IT*dHONT6m_HHrEjzpbLeN)sqIJx)rZ zB??E15zwO5r0w;`Stgcx$twk$U?(^7=q*u&?AFV8Vj=L3UB$mf;kzT{H%Sb#z{O0K zJc|-7xrVcYFUQ$DQE+zb$V`rqMo^;imGShqS&gb39LwK(lDL7WS26wcr|KTB&T|Ui zDFpKxl#}nI(wN``4|*hE77GmGd4$F&YxpPavK)q3zQ7Q&~6-I_K@HgmKqRp zV!-F20WfCCYTym?uVdPynpw%mz4pe&(@U>Coj&Ure<92OD_Mvx4c7qcid7;}<0x%y zKUQFn&b(E8J^}?YYf5s!?NRTe>=lk3;v_~3d!vm0yaINo-u~u zAHzR(anu1nP}anap(D5|;$Pw!pZ;$k!}R#iAQfPF#A{^!eD?602=Zq6?CxaE+Rbc1 z&n@!{+T}o1%z}0u>3ccZ$rJyc+jk%(f@ilBr{E6^x9FrU{i>E82+?s;iBCZ91ZZ*8 ze$pu$VUKI=+xJtxvScJxk~S-X|~2OS^~OECX7S#ZTV*kwtrzX&jx4)!;&$CQDiZEX#ey> zgdze$QOP6>xBGt_zZbKReUL>F^2*4bD3qOT&7P~v3Y^JD;c|HvSsuB4(eDerYTK52 zLc)z?F@ZUu9DN9zr8|I|ZTNJ%&EZ<^{W*#-=xRrTR8SCeAf$wvCTDt&pIek*r@(z>W)sZt3yrNM*f_ zEe^BL9BMEYtk)A;5N5fjJIZRzq*&^|lAH?Yq!r<5sUm$;Wd;P&-d6tL!l=F;e1(z4 zg2t3cRXdyb%@ThVpS^1WmZHG14?Bp$+y|{zpAUosDlP^Gql#1&Un|?>ZN(Jd!w`vD z%9QWkL=cUO9$tAAdSk4|QrYTyu#-`A=vOUu%Gmu=j)IFX6{Hf0YeZuc?gs>SX6|KH zMttUWWASVMS^gj${o58})&rYdAyw3&XGYpoqfbkm+fQBYQFyKmaW? zQ8&CO&W~0eazG#aki_HF*I#U?e=ooTt!(#GV|c3PotwTmy+G|^ddvnp{hcEmgpsrB z2l+LX84T3=AQt(FN#74=Y^BX3&Bn@lB7^4`2L`ectl+VvhL?@bkFUG!e%ZhnjH zI#`vl6-k?;$FX#ZE0$5CvF;2TBEfLd7};8lWE zt3)hir`KMFjhJTHLglXlv`deCVW>6LC}3=4>nA@3pisWd4!;>Cc5c3RQ zlr4=(uS5|QkkXc;%pV&!6`1mf7c~{boEI(Oat80dNB9vwc`56fz2r7x8$2M5Stu#k z3#ST=FxRKPgk(hcd5}m^z^-1ls<|--&xPfV8-ARpZ97QA_H(m*4!)?bG=k^WF1O4a zU~kh6v&O%XzxywIF=rgkV0caJx+5y~k6y6Py#bdaVwzi+P4f29( z6NovwS@sW4@v6yo&0KA}!F1966C8D^e1|YxZMON~spfBA`R4)iR?D6kf;ySpDjGnY zOlPB@t5j4})C%W9^`~jSZ#Bi>+HkQBZS$Xw;;`WzI|m6a)_y#6y+EepHOdg?^RQ0b z4qcZ?#KZi-XixCs&_!iBBrSnVi;$YfXx?_#%wDLtriG@FV^NNpE0*F8YI)s84#>@j zfa(Kdm#Pi)neuc|-ZK(lYpn`U36$>L&7qw3BrU!TM&18~dz=;inU$RAm+wFQWu!3w5s&jzvbY=DN@9^YZ7`ygWOJv!*d1o~OCcBhFV4)MYLcj}zA)qK-F(&M`%7D|v-@E_k<6t!^D+}} z=gbDz^$BY)L-UHCTqc7+n}d(IDJY1D0jTbhQsFU!C!UF}3-Hy~CB5S76^cx58km%9 zp=n4Nb;0Ijy=f*4OVsx0xcDh#xHm@IYZsNH&~BoA)j#lN0< zlD}JwrZ&Lz5hqHn7%2VuWT_FiW>|Wp)GzK!u%3=m6}0?Hmf_z)nd}NDV2BzIyq!ce zwAfib1;A|R5AOZ(0|p+12<4z5PTN02oHiAPr&}*}(@~aG_9GY&4pZJmbx%nu^bW`M zVU7XVzYF~b6jswb&fGvga%Y$|&};i6N(Qq+IDIyZ17;pj_xQb2E*)n0-3h)$bUSty zU^ttBPPFF}0!j(?5?riDT0V)!4i)opaJa0f*X*Vc#8_8Ryufaz;#YgK$vnf^|0%?Jj6!7!^m}{<0MnRZIG;|Pzc0Y2 z$Yllv<6Q}VIqLqRY9NTwn2_8<=i|mx5Tw&NpycDZImX-7zyH4;%J3#XWVM;oXWt*U!|XV#2m}bi zp~v8W@||HNH`04evZ#yjxQ@A1N#3S`W=$)8%@Gy7JpNfSdQp__(qv$1GsB~hANN=1Al zHo&T2&-)$jLzTRkkHu{pXrSHh5}9qF56k^`#qB zDKpo#SHdjlwPT0geSA({hG5;E8|Lc??J#EufNNd7MgEF2kDao5hs8N3u7*+2$lv#O zG?&=ClCocDvNOnV9HoKVcYq_lh>F9$`4G$BqcHe~s9=3su~h>R6$y}h{^G@Myo&+~ zmxObfox)_ePh;S(wtbGybX5J%pMgJiQtNhe@;DJ?wL8T}DF4WQ_7KP|v4@JG_2=*b zyoVqy<_|--M(svlE*H|^9FtxI+y`EZaOwcUZNjIo{r9kw{ZO7g7R9>8m8jyW9#Vcl zEzMB-e*YfZP|K~+%&@7?2L9j+Sk{bMfn;7t-7Byq_OfeJ+xS4-X#ld1N(A2go>mao z1rHI~m&HFzjmYvXj-1JyXu&_Iz_L-;@-apz0VifWCS**UT#> z(^`IgTr_1MQQnknEL>p}CkmBA-4WrYRf*Sj2B?kg7$ zly^(|EEd$yy6vB=WH!3h2yD2|&vosYRzH<|PtdArY_$6;f}w8_^biZ(D;@FToNS8AsRBWZ$Bl21^%`+S(b#+R{%RPx0y*VZC{}P>(S8 zjbUypCow@DXZM!A1RD+iUD$&yXyYnrCQPdRI*7ZV>l6hpnQ?AesFiN53HU}Gi8pSw zggS|PIarDsM9}H4Q%JTsq>zra6T6hpa{HbitCP)yOGYa)vGYWMW*@fCQBBy=?B$R6 z(D@U*DZ#5jMpjv%8bt3_u5i35mPmW>F$Dd4nl>xz0pN=AMuoY(unYT)e^(Ww=oz)yoaQSIW$>KoJ%G zJ`b0CmG6Og^V%Ntd(UD1#;qL1%EPHnwHX1?mVa}1kymO)hj87Yh?({F<#SX9 z+v4m&z#E=p^ z6S!r@F{u0dk+=|1^mq-LpyACTs;fgCql`n29}6+Jm|0_DPk6LLP5io0GckgLVky=2 z2JvvQl3xaH??JpXwejQnsp7wz1fK0=`}ivOg&8`yo5&krK2mFN_$?tpLPHd(2Z@1B z2Hgkrc(A5g1ai)MfGZlR2JjLX%z71nAdG$J?-~ryCL2O5{rX0>A{Yc z$7Xe?{Yq`DRvmnFr7xoxr#?X+!b|4Kjtc;d??g9WAP}6@ zHzBfac9qRLkcV(Xk|;!b{>*)(@~C)WbL-La>#o~`Fcpx z!zFp&Q^Qms^;Enp)R$t<_I&CE=WB~1S?I0Uejk_2edP4T7EsS+t)~!D@mv3}HU@D` zGBYfd3BW}(i(cfT#puxw!)gK$!z`7@5l%Gk@Q({(5@G%Moj+%L6K12}{L`!1o$io= zQav#qhB+b`-nObqi*zwwl#$aCC1&pMQIEuo*{oC%IMI4^P%D3U;bJffUCJpws{AKc zK3A+(0uBg$H%v5Jd|;36N!0`SYrfc)XmEkHmt2r>7$tGJQ1dU3AcX%334USye;O$M z(-u(CSh>;3+(h50djYqPc}=0MpQeE=+uFWZrIQ(XXLViepa&+ifGzW0pBdqinqsP% z>{87*KhpX{S_%4cUg|5UApjbtWP&D8>U*ZAswWYSv6;2t4SN8k#LS4X0@LEwY(;+yg{WheMmb%i-P@ckUw^eAhjr=DWL-Khz$$9Ye2`luf&K zA$}8{G$~;R$n{%)kok%iwL^i9T$ZH(f0qYCnV6X?r(9ehmI#!(-#p>V614H6M*3#r z@yNKyNte(EBj@RwDJkW{_pn^i`_QwTAdtt{A=N-V&=2@CJi+fBOIZG=3%Fc^;8ycF z*_E0p2R@LL{5qbo?2Wk{{%Ufa;Lk~&%jGP)q39EIVxj||jQ#J|BULLZUC zXsW|$-=)V|ab>x(NyVVvmu6fY6sdO9HS2^c(H}&NP}2FAUj{CQDd{^bF|5ryBB0G_ zBFyB)nw-{$x+?KQqThyg&c0lWSr|k#OMQ83*lgE@|GXzigjF_0GT&9PEI%mu;olV*5AN?r2T#n&qjtz;MGOqW{Qf9w@ya|6NGuRasc z;}<9Q+ZRWJE)>J#r0l=NO+9F?ou=dBo4@KE>=)+d5X*@#J9?JiWwMyvNY?)ns}_>=ottP-v}cOs3yVP2XB@YpMl;7)&YA>`_;!-1Nb^&Cl6m)17W(b`N)X9O*AdefyzDT`+K}PLn3A8 zs?P@JBS1y2O^rWRXYQnHpj@EC;p~{YS9v&m)?`j_q7RJh7l{@Bkj!(|Eez732PM|% zoVxh-{Lj131)>5^0MN3NUlpJbe=khyEXPn8%Vvt1YOW10Vj1qV96r3@D_t|c#ujm@9G5Wl(PyA$laWXuoa4!YEo%%p&f(=h`YE-I^ZR<>!^(#Q6dg&F0w ze};X2Ng1`uG;DO3xYxX`Y=yrl$@uv(fBc|R($x(wl*Kj~i5D-fs8D~XbDEA#NeM-J z>Lk|H(fbbG=bma#^X_$!azTc^9|hnQIhIypuA+_+x^U}lpYS^KOk;>bb^NF8SJG;k zzJeoNQ}c=8(Hzt;dVJ!ywBZc0=_f5Pqg=Yr*;d5C94X__%`- z+~ueBuDNpjaaeLe9?j{Ml9KM`?~GYE?!=Tnisaba2`Nfej``Eqz^?sVcD ze}8foJTn+Z_ruaP?hC#V5HlLiV0vEVc>8k(3{#pG>YWP~s)4tAP4o{hLy#p(^B0x( zgJ?kzgKxXM81l+ZIdg7j^idw3KETp|fMMH26mPb(2Cb+F!4AFcpJ=H8G6QV~IXXPI z&l?2hBpc(dPD>7*dJc+}V|t>2D?_=W2R|McP2~?@1_m1b;EdWS^LwuoRS0}1iFAFt86uvg!^62kjqQIwr-eMt65Ma z)J7KE4@-9p0WR3Js+vYLSbC1sNG-RY7qwETuoP)T&pN{ah2c8lOL@xqIK!_4&C+5q|D z2DF!A{v4gFSz19sQeGaZwr-}10F*GZte>5CU zO4Nqt*F8>XnV{*c7J49nb2IEkK|BUxIlroc-@0RYDc}el-ky&>pJ)_`Hv3X{^0;pJl&B0Jb_-SZa$iFo)#5OiIgpTeBG z;6qqa0`mca+<><*1Aj!FesNs7$o%AF+t_SxGtzwB3a=uO*KfcSpGP!Lxl=NtEW*Qe zUnYe1V_$1}MAARIidMHAYmH2v`p+%E4%`y#wY0F5DnR%|n0}a_dM#-Q@1e#_LPLYz zUnW!PI;ygpwq9@d;+_l4OiWcm`o~UtrUC$5T&?5Oq@;WdzfLln?2XbO(BY5;(pb&} zKx<1#SXfZYG^*5<+<4K+uI8%@%7pY~Wa1+RcUYL1Bm+8t2yCs%Q|^>wzr~gG8=nPm z`915WCj!>1jP!-|;}bu+y4yRxaCAjqEdN*eaK(?|NG`hL32>Kr7qujwaaP|4Z4o~B zT^@X-c>2XmIT#d+r?m*Ckai>QxJS%=@25`@bWWJ<@Nw1RBNyBab74ZmE3~Oac@uea z+v&Sp?e?gI(ERo!c@YcO0sxytwiH-|HDNZU%>c=G+M|NwUTw(ZitoHf2Hcj(4>rc? zN0IQR5$5W35(9)}8HBQClu;gJNpQz%19++)OisfcUn~NaxCxpvM9FsYTe0fM@G4L? zesYx`i{@xwO-dEYUZX(ZRVQRP3>TimoEG1wjE3mV9VLqZjh)%p6@CWHl|>kVN@f81 z213U+%0KyBN6_`dXtSN;??#XtMxckX2;$f0rxZkb41=zNP(wdJY2bF*j4tB`pECBT*t#~TdslQ$_T%+!72 zizfD@mYcfze>Tminth3ggxeiY$_Yd;9*V%BT!jgPaYu0H&(OCZY&n43@|I7=jnatE z?m*m+!sEdwlZ>{8`om_lzR1!Sm!4j3sBgp=uzmred%O`QZH;GK)j18WH}KlBCns7$ zlM(azS}v?zP`A1)=$r$aVW^0`G?jnS2fyPW1u05HFB7OS134Vn!t4{B1SsB8O5LoX zSFT2hkV(HeJB|!t+3Jd44@~^#FOkxXj2(VLYzW0KYWbpyZHZaTrpdi8*|8cKw_oBl zKsy>^3)y@@Cpu@Wj|mk9@?PA5Is7DWwtrZX8Cb-D#DwjQM}{nR8B^{L&;T$ zh*UyFi|Nq8?}d|8&PJQ{+|pNBFyd3BigyFjEh!DHg-w}>ePXRz5VJM-kY$_lE<-vj zz4Mh)oEN~F%B1D`OaXAi9$Y0Xl8O=~^6imo-Bd)^#gA(RAf;;&vqUrC>y@+~r=Y)M z6|B+LRx?k5JoYOIE?1KDzo79yFHl>Vuer5M>3?P!G>x2%R@8feA z{I3W}^bxQ)UBKr{yZ%MhwU$sNhglL?b=`y>qcL6ab44*f{JEASYmWUNp?*;zNjOX~ zsdvcy+sUd&%}+{V;L0he5Giw3@gf2|5q3@j4aH)(^PR z--^uB)Pib@VQ~I1S8G!1bN~u66A{h*pF`*3^0r^%+1TO?bORF;G3e#wB(-g8+S{4@ z9}XU_jy;JPJUHSPC`e4j!IfFdV$&K>tei&UGM@=po#3l$$Wa9us3qoG(RQi!h?!0R z-wLd|OINMw6~={Zm%-_&N5o{*Gmk~Lr>hiWs|g3hJ%;sbU|?b4Yi!rl$qO`yIqnRo zSL?y868cm6D~5;V`kph~$O#@vOi8Y%{d%FVxG2nd)PK$9GW(6#TlH{H40-4GvD+J6ht@g?Ptu5gpa%GM={jxkNR*5$m{QZ<{n;~X#)4Os zaqQqeJg8GTm0ycQn?U^})1t@$WOn<`AW1&xV>z(cj^QBAL$mM-{tHKJEbea#V`ITtkDhF;epZu)6$s{h!KU{@e6&PJSy@#sC(^5iUlefah_b@a znc6XjGJHNq^PE9vIL^DIIzFr7yX=p1A7}8|-ySt>B|6y+m88gPc&ssget(~4qh=h@ zV73!iX63%)q@Y5EJ!;W>ooRD792ElkZEi@7O^7J(A5bf}kuaHXpw*@ri{GQs>pn8b zu*$@?)8m=~WUqXd6{zJI#eIze0-c{ie#gc&f|aE(i7Xvg3}+bl6Q%e@_R3jMk8gxO zjnLJ6SF4?6A}q?Ov2v)0~l>2<>5uPz?D^u z&kTIMmD5apG>P;VlP#;DrlEmtS>j>t6~5!`RB50{l_V>!BgQjAnuK+v?_OA3498_N zE4Gq2K&{ofG}plD@~VJBvY@vM5WzdKnc@aj0Q-IB>h^Ehp`{Sdm)jN%7E@S`BTrFy zMFP1mi*Z2TqPt@Z2c(GEN9w}TVu2>Q3OJ-POG|wFZKVWlWqiH;A`Mr*yhgW60<3DEyCRwmJKOMZy`^ai22t#TfHt3@t5nT1SM zi}@7kh|a&GXi7(Ux30q$LJ{rU1RBBbILxWgg$t$R8f@cNItTs5DYmLoKDB*jz9L%M z*;Q2{%`^K`rrLkhJm>ErPa@0p00;766G9WXYo2&t3&&J;3Q~CSH#YfcD(J`g=!24c zPeG(%3Vz!?ZfM+tGFydzyy|?mMY(86yW8ocIKu}Plk%t~XGF|TBJsbRHXbuxR?%Pd zuYrh2axS`sS2De;Drkn>Xphq0cU}NjL$waO&YQ-^CV9rs&IY?>jV1kf;X7BoP?cI3x%7!-`{g5-cDEDiD64NR9Mtr^Q`q%ljV!a|cOer!$Mv1f zm~LOhWh3jPxgItz=>r^}=|`EQ`&%ueuGTi02HwMBB`ls=9|Yfqcg_!T2NR<&>Hvlu z=ziJ}Ud%$D&iGaw0JgYH-TTH!)RsVY(NDzCMnD7Ce1#a`DZrY93OcLc05ZC^HJotqcyRrtm@ z3AnlePr$6K+DV%B)GY&?}EXv2$`&~ zSfA-4QGc_dGsw;b#}l3^K~TETQt=>@M1yg;vec=aJHl$k8HLer35(|7Sn%umV_fJ2 z@gLQ!tO;M!GG}OXyKla-pzWUPhU0LlQj`GK#EX4fAC3F@_gMpWi2qW+2->NVnMg2j zUH(DlzPN%uWH+IG7V5-@6*?M5bG~7D4jp#0gznXi%b-u=OaHnv;e>#ZINC_&Y$B0i$ih8|OH3b4m zc|Ic_MdWQ?cYB%4L+0(iWbbQweI#689FnE;+S7JVyu)AU`;x*;ygc_Ubw*clc(@-0 z@UfOH(YoK1`t2TM7i&Hb?mq4vco#8zpw%6%fJ9J&_bE4j}%cqtV;Bm%VmgXov?ug8X*p9Y?x}mi8xC7cf z831*WLI~^t;BIS&BD{O7|bJe?-8$`33D7=tP<5Gxi~72s&#l@y7>vR1Mm`X}(NFfn4 z!`s`|z2F(?)!gs@h#LQIQ<;#J6S=BDrz|d}pk~II5x8N{Wr92~@Zj2bazyr(e$wB7 zCfK@FC$m4p?|hyW;r}p#(f4LXvG=V*nDNaF*kuOb#n?eIcip0cB(Un-$JmlFvFOt^ z6qDnsst8RfeM9-EZwC%xdqfZd-?z;Sz;i#H?l|~IQ)R;L8Frtx0bBn@NH9y`)X{aj_SZ#m(S2ZHus(%m}WB! zJpEGS>%ikl>;OTm2S5|*^5UUdY2OZM64}F9G*sIuO@G*X!ezb3V4xWn5g(S&Y<8l@ zreYAW5{6&IF>i*GY-(DGjEss(0I&&f=spyUcDj0%-(BoXX`@{H-L!+*sv6}v86D;C z?^?vCc=3HcqK3Yj=H5kO&}uMURb8(I%_0{YcpeqIUvxdF;!iDnY)feLc5CfRS z`7f~&_d*1ZfIsVqJ}|MdBwr@d45z5$c6w`Yc8e!T5>j&FcB0)JW&^@@Z{vK$jaE?H zt%0()#D0`EXEt?r4MsL2pSaI{Lzou(h7x$WjHuO`k_)lphzU^}4!Joy1lvLY8R-XL znF#}#h`f4T4K;3sF5Pdr0XUv_bwB+sR^v07_Ytv4nawa7<`NSOk|PF-lK(4Y_-#IV z0VHhwXKPFjfJ=_Ao>rC1plj;7w>dshDcT|0;8ZemoNccy_3#i(seDca=|+KAl=I-#|V5pRXHRl;MNcl2Th?4vrdxWfnkC6T{Mwgv>KTMO} zeME;-E2w%tc2N7|8o;%52YzrNf(BbN;p_2oqxcXzTZcV3&P6r1n}k zYJqP2KTyf6C{D^6+sPy9`4?}9SGU*50L$EY9}O}lI%_I7Vj(*C`uS=6$O9=J47+o9 zP)on`Il>c~mv2+&vk9SCArg3NpW6c>+1d5V{; zka6+RLk{uWI4WJ-b07a1(p1b2@8=Wm=X@5R#AZ-`Qt4^OUT@b8dr(dz6}XWoVtj&I zI%7wtX4H%xd~#;>t{u2K6~ZC6pJHQ}^gwZQI}6-37#DYaP6L=7{={`%Qjkc#TY-5 z9ox`y`gpS!4Wu4R$yPqUhw0(G9z=e_d%mFG746JRPxdK>KoND>(Tb4~mr^{6ZlqAD zpHIxeVSvMI<=Mxo5g~~#Way{od~Nl}a+}areA~ifdCgdKjmbCMo59hIf~}fL7dbiZ ztL-0zKOT%hM+wI+Slf$nz2DADlK!}7jO1rb&qnFTP>XsX*aHD#E$Az@-#5J1fyU*e zfTcK>>Agj7l>cTupHRAnDPkMhN7E-T2x9Nxu40O{Zo;OXkq^=#J`2aAwJJmmuD}{4 z@Hpt;KFvT*clW~11*} ztx3D$XmX-tJBB&&@`{W8a=J9?@|im7YMRTuXk+5z73_D(W@w|l5I8%DA9ShS4=lm} z)Lg%P=;kb2C#Qx^01ml8GZ+tj6swRB_)`SQZb?ws_Nd2&v57H$u9p?RCsH>~8$Dtj zzZZN%+FE3+Ug^$yp5IqtAg^haH}1$SH=&zvI~4t9Zp;A6S%?JCzBjXK$bEOAaCX&| zxTL!s8{VUK>rD$|_TW{0sKfc|{nC5a1ST>c_%Bz>im2#(2P8hJpa`TRpJ4Yq-)CCi*DDEK zhdyY)<4)AV7u^ze=72T!?by#t9%AGcJY~4q}^N>W0%PYaZBf`NM!Ea zb7=0@pX5kBBHceKkiThsHres9=oHPdzcdF?;_c7Bt2j zmd`HwV)G~&jXR5U=?Z=`$95B+n-DUIF;EgkKj?seuFEbmuKo z_Ejqn_j&Da)~lvU$2}>(p|R4uxSN>{xRE?J4tf3yr!O!A?pxbo@o9O*1#eDH*YSB8 zfr+;+kL4_Q?gFRGT4dd;CQ}P@{CIw%-V{cI3g5UMaf^ zI|^GMhCMWTsQG5&o8CLb>sjKB;R!n)hB#;qidg{0;(`mxP2iHjcdZj#?9W)b@5a&L z*u$gnz-1b}g7{L<^Hwv7N_@OVxY=e`)Pw@>r?BPrLhH2iLjgnX^Ue#jD#q6h%R>}ezLt_Jlyfl8HcM$@W`ajOF1)(x^%E%SvCp?*g;)slr*7Zs5aVfC zR5v~h;TV+BHb-~T)6oU~K2m++v|B4%oGcW4KBP!lvZGeE=A3G#mj-h1S8388Z z%eI|hMEe*bcQ<*V1qU!@9JxQesou6xBfjO*4Tzg>YKGUN08Qp8vf}B|T%}A-^G)8w zqkTycMf0phe0k#E^dPCG{zNCpOo9moS6;2`ws9W@!~i^-wWuIkc`6sbcdLU(dCBkn zRS}*)`}WNa8f_q40zr|?WZ6$0fl46PA1$t?-^k5=NXpF@x|FOCy)0GNb?jt>)vY#c zdrS0J3-v$4FcA70jwXtWz@XkaEQ}pY-wsN_E$1@ohl(a?Z%-WVp}BVLHRMO|a5jU< zFk&T|2Z9a^eBuA_97)P3B=R~ZBqs-+?m;jZq{K3Q9vk(0VfR-06C4<9Q>D`Zg~+}{ z!AOfYc4S#sJ2O}?WL?KVjn*cmrJ2A-lENc4s^0_cQI439k`b6);8aw~ETJrqFwV|a zPst36sO+qim>zjuP&}&rN;G%PX*k5iY?3!HJ?yo)N7l6^Q8h04b*KLe1M^lW4&JCv zGx$>_7kTSZCF?^s!9%a(y}_Kg4_`RetaZ&v=0*$C)l1<1PiYh{N=SG|0pR(VexYgA z-OwT>&cKh^SFh{%*oy!8un^(ck!v;2?;Xz~*P|rzw6eC=e)=w|{5jhH`5H-@Lp(ge z!^l0SSI(uDE@WbZtJ*7(d<_;7#tu})_cxAn^ZXS@cg#*U8G zd>#PYZ#0}UMbYSUP>4AyS3=H&>BF}UCqtded4f9ZxrB#EWr-YOils_3v z;8PE(hh7U}mb0^Bn}xgs5A=OL(Rw^-cKrY^i9L-FwBV0cNVV-Ltg41TSX=cU;n!%4D0QYe)$>`~2o|02DUkSJiiWgFo6O*GGVv56qk*jFOHp{PX zR1y;EA$WLbopNI##2104hSR4Vy&2Vhxu7dyi*15?D%zkUa@Wgwhe7~%UfgdpJf9Jo zPM}9g!O`zhj=Zd4B0Icd3$f!_1^~_`OzGyeOhA^NYzCW{T&+u+?4hW;X`j$@J_B~@ zkEBA!K3=;YecBp8j-54fZ<3HL$aj|D7}?e~9+2#6Eh*Ppz2x2F9djn2&pLKKMq;5BwDs^n({ zD!Fe{ABty$v)J$aRx5L2t8EeZCo=kl)F%3LF3)~SBqB}-jN$0P-y?{kddszK;`u%QXIYTtGNWdKv9CAKL4RNQ{cXclN%O<+j> zd*`$q_iQVv!Z|eY!?(jE~m}PF(v@R8)i6gAkvc7;)Pyw%o*kXHcaZn%${uGd0<_ zlMH3LzfaLcgQ)Ynp`OwR8hsI`fQpY~h(47qeu5%ukAK zd~pwC;W~27#rBH{sI_%nFs(PCXy zTDEtNRHzA@$FGcnvqIXbWolL^iDjS(U`O>Uho{rU)r4kF9<_ml7S`r!5EH(h`auB8 z!zJZ^rc9Ik_;6Y_)3u@;iYH@Ap~xc~5!+89srroX3T+w7s4P=^k>7Y!ZD zoz#<26Xltf6nyE@Jk|?f#^@QT=$z8*W`p(6qF2)HgsQ~mO-M)%4Ln7u_pK(9L1-my zb4N=xw~e zU&p9l34TcZ60I`ljScb1NCP7rkIPk<_QrZlkn%?g@t1V!wKPUKYoV>!P7*^I&;y^K zmb(FOJzzJdzIgfHL-2pq#8nORpa6HmUjzrBodx^CVg2H7Y(OEVEt|P-)XUk?Kbz!b zUIfX5JGgAjsrf8m*zZsi`y-A7bYTDbtmK05)-!wMXNM(FInZ5|f3y&^!B`#O@ppET zZ+v=MO|c6B7H~>r`ujbqQv!WdKC%a0rj_&naYpK|F16z6Jw!V z)BJU=)tzDT54q;O-yezE_(_|E{r$#Oy7jVWP91h?*mFrZMrRfL(F7A0DXh4x#=#Jv z0)W5?-}m`ZM_hL48VM8}KlFs0di1A1QZ%FTYAgyl2b3Q$$68-6Km|QP@>ms{-NHk6 zVj&k!LFNlv6fm8pcpO(2gg6xwo{SXG)YK0n_5_s5d}A00-$V)wRi4iYzqR0@V`wJA zgfG9nq5@GO_hir^{B75@~vjrBmsqm}liB6^U> z;AHT#*WYStYHo^!B~W{e%C?^E9=X^_1L0bmRjuYX_0n4Sw>h{E)uEqG98xkNqGFLMiX1YD`E83q}@!3#u5DW2Z=R)V#*6_{nD+47dWoP$S(GONbH9n~4NM{}wernnpyj^=L^j45H9N&Z8rT|2;liHY}MU$Uzz=4b$j0LxRa0yeE=Vg)+uPNtp^aiWW}7wS=VvAo(G38q%T7 zfrkOhJ+!o&6y>0K&eEVDTS3~ZjHGl-ilAEgRDTTQecM49z$pZGUKcD8`(t|qTl&b> zAIqTB_BjOq?VEif>Dx}7mw*#du>~+QfR0?jn@mwPS^nA?MGN|C7YwHiWT!;lGWMJD z^q?jRNu(vHDO#ae7;PGlmUPT)e9v)Rs5@N@G&j&HPRtHFoy&+1s3VVFS!tjR|BuSZ zA~ECtWE{Od&@828dTDX-ou7u6Lt!+sHKI~_R*~UG`vRx|rjCz*Bgx5Oo_PLalg3vjD?rqccCdQEsjtzqd?eev`(7Qfkmx&_Gpe8xO4j zDhV^BFnbLznCmpT&|rMAKb%vFL(VB~l+Ff%MvTPYKMg}09*Dc&qAu5Aw!VguRu}g* zrrxx^PUbcFniUvVw(c-CeAw2?`d$9aEJv`0q*d%L;xe8+xXUK#ODtO0DRqQF_{n)n zmdo=%1taayM&`Q|8sa_P92Xtc0hH;d^3^^XsYK~92^$>6J84(m&&03=#9tzJtHxO} z-8I$=6+#Md5!vPvWlhOsW@qw0a84KtDYbnq#&~EF8`osAP zeR^vNrG{Mn)Qr61#egUb%Ik#$P>Vp-z3rE7qvKm=mR-9PQT6TP3tw~k-c35o42e~8 zpboeOI}Q^Zbv8@WxucXZKi3vppeG z9Ihq}-^=IlAt(&p6vc3BY*~r&&^kD&L8HqhDS>-$SRieAxh+@0x5lx7-BiJ`*MqY+ko!fZE z0C-s-E*6?VEHMTe9J=|*nt~_&7cbUnuX-?{v_&%1st|4G>8VL4Vj8T?A~Ig|k}MYo z+smC~trON~EWYExhj2b5HGr%9{qhkBwLYXOJw&84+2 z#k2cod&@im3sTBA1gX!&M;U-(O?R$@{F%=>g+~*g` z|I(KuQ8|}>y0YE5^{c#p@)j|&6YKB3DVNSndU>mmxg#v)CzXH9D5z#6AnEy!)R9-q ze^69wmo|h)^1uG~t6DLs{d5+elo5Pa*_e=e%ib`D(YtOFhJ@GRWkg)MgubPjrR9Ku zB$B;q*I~OF+p;)}tNw+UYbc$=I+b@bQifb_Ed zRpF{AZFIl@nLYS=-X-biC1g`(;R)uG-;~U?%rGVc?T0%E!F9LM6 zD}!X?YB!N}6(tZp7Y6?F3TC5N)!Kd04R`WuH|A`^(~pGI>s?4`-CB`J8@gc$>}fmo zYseLE87LOUzfRdYsYJE=oaS0oYdLE!LrlJt>n7cx2IMIH91f+4W~_`(ta?SKC6>B` zy;6c{mVO>h7?;(J`a1;!G;sYgu30^<7iV&z7rXnB5y2<863%`=Y25RYwv!5tO!sxJ zR63(&V3glnDN7eD=v+ooB38;@XUU1T-Yq9GzNlpF6|O(Q|GIHWZ*x@Pjp6x-bcPc zx?iZ^HYoUqPtjSEV8~EX;+l^1@&;;Is=<&}spnHSsV4nZ46n9&kXI1=3vz(-pFaq_ zXPo!}B_bgu9!rqyo3y<=D9j`2tKEGDBsw9%a<{b6k;B^j+|EQWn<=sOm7+8bFOE|t z5$V^Xp4l&E$V|@#2oh_0fsI0yUx(E58IZY;0=~(*(_s`6(+vE2k#PjxT^OkZ;VAUv z1PcEa8i22*A}{`ipGsDElDk4WX9j@S=3QgEk+|))6?kXV+k(-KV7nQkJ3=9VwELwBOn_K3SVgEpGzEe8)vV_a zD1G5E9mOIp$lc*yuW6T$glW(5h6-__Ny9AM@a+u8In3+HsEzPsc^*=nsD3MKX|YAv z`4<)dEpjwV{M|VgYSa#NTdn*YFL8zdybAGp@e3R7dHjpS-n4;VbmXh|Jw3!c#F@$j$QlUExd9MFyuh*zy zJSgx-b7hc5aI3)!Xfi(eh45is0kFHvpvy;%26-_tI6q0H3RB>Id*{aDdyj(4)e3en zwHauEp{J>~-`jM6@$2LYBpkXDxp&iVIhyf9{A%=BchbiSFLbJW5LP#E+F~orZOLS= zYcv0Y-kS9;MLGM){nNdd(`P$kQTb}|53inKz`m&$8^nGVh)hlPHlvkzVt{N} z@6P@3r)hL%BcbR<)qobs;_je)THq_zTT21{18J0 z$5Y5p7D@(HjA$cww}0qE`s8jv)G|jml0354%+_0@p{YnhVpP-dH<)EgJpAF8C<<-(2>;9Zs!P@lEMXl< z|2C;z_mlXV?~82(f9c*FU^>@q@f=`OOJZf#5>IjoyMQSR(uBFPG`z4ljePjw4qYdp zU2dM_Bu#y@G{il#7zCDyDQWm4(*O;+Hq(jsW-J8v)ev8Nt(~w`Fd;ycc(NCq9noR< zC1ZK7MtGdM9QR3)Ox&B+hkeb8_qg-Gw?Ey>$-ygd9;0mFbKGa6L4nH4NSWj0Vf*YZ zOaT(QKDjLabZ%|H59sH0t>B1FwE}P^s3<4Lxi@Ra#|bk!d`A2-VF&9^Og+p5KIc`v zLM_tGgSz@*0AlgxOjP>aq;n7nv(xHJ%FVV}}t)=tEyW-i>l{8|y#;KVxg=iQ^1w>L%cFG!E-Sc% z$NU-tBgk^*56?XSjJwC0$hS|c(WA6FzXYtYJSX*{IvIOm#1L~H>kOeYJL|yRd}zaB z1(ZvXKC2w;rY>=A*A)9NC`TNGF-i1C5h!W;q(foM^gOZ}hx){nXM2BtFgozc+id~g zEO42PJ3g~l+e{{ZZ!`Gi{%XX*j=YEuunD_5Og95K^{W3c&?`14tFQGfXrU6yS3g{4}#h2g&au_h1jkDH5(q+ z3=-csKpM_gKxbF_8%Ej(Tr_BM-Hen75jY!Gn+$0zya&j!5{`zc?T*>{$%poOtnr;? z%Zrkq-JpwoX7^oKfKv`>wP=a(PPHjx`h2jmKiH#0HiKm*nO4Qm4)i^rQPsYsXS)D> zO@jfZ{jyf{`Q#7p5>w0%xf#o1*MD!KI-&3#sN8rT1VwBOm{BxJ5 z?5+Dooir3Ot>~{WLen|&Uq>DmiJH;UvN1+W70$eamoym7uuu2rP~Rzxt<}B-pmAer zqo3e!r8vsWQ#72pfpx4wsn&pHS72YXNP9otbA5lgrlRcDiU`6A_~ZS14!iIj5OYZ5 zLdZnj{-7Vc_s*B#W6GS(!QpjG6P-3)fWEM*WQv#g_k&V(3)D&WKrX6o(Kz-~ zKri&enQJAXm!gU&<-SVeHE0W{I%FrBijnt{K9aqO?}5e}aDY3N|fJ z!YW5YgBG9|3>9tPO)t?3PO|g-^W@6(>Jz`J1C(6e6Bw&W&maM8G4qBMKl>|RF!FK` z-hvwU9?S~LdhDYwA4~Ck&DK!MXY7cf$ngFk1j9C0lKvz}>|J1*M&Yj40&bHsTk%Fa ziQ7-n5GF^Od(&TAItVz_i10oE5>c=er90$459~xDV zj|L#wf0fN(-!g2FbG}^m=0gKK=LIP{&xRAMNPHhxVjt5CMy5<2NWZK{QC~k4I&Y}| z$ZSP1XbkGc5Hde8h9%m$kmSMdZcyHyA7}}(GB>^qKRbSX>=fD_HR7Q~Z*P|M)<)S4 zK$BVUf}8r`3L2`FO}7{axn_y%Te(?3zlue}aiCkX8qR3pzaEsURI)pm>x)4jXuMH7 z21McLyMr@#&BNAqub>Ecxk{AE6JZW|oww=J<@w7|zX6zxe)$Qs>-dmfPV=`y*R6sX zgaq0T`ewK7-!G7UPbU(lfUgIu1n~Q%W28;6lBFj#LM&i(5SN<-$f!Ez;}=r<1uS-L zifpp-yY zWRWfTDL_L14b#@s&%ZUB!+5)I#NMV)uGS|etXLl}NKiBK&xKE1*a)-4+QbE!7AJjIWc{cztFIF+>J%NbUkcy253#m1nQ zic6VdjCJ;IQR7n8TUyPi?#~8=WB&V(51o2eqk?%I=m`{?DsOQYZ&c`B%wPBDH@EJO zgiM-K&R!?|RC%!{>C+T>bj{EeUoUI-yhj~}mU`bWjGWagEW`NI0z!niCB2j^8_V6$ zDySxZs8jzdsQx`tKi~f)+6H^raru?)E`_k%BD8oL5dS2?>DWT?7`LicYP^|J$`WDSwjF*E0b{O88)&EsxI^E z)K6}oP&&h~H-#gAUY&3ftT?%GoPxhAtIk9Nx=AOYhkd?Gx6V){|FP4(M5}(z2K@&2 z^B#@Mvr=tU7u>bSbMPS^BB-gg+(LO`&>-Y`#%-F&b;WeEbb}1GXV4Vw<;{uo=gX^_ z@_|IT3$DyGx0>-YzNvASv7 z;!mX!#W`JlZGvY2D@CXCA1hTIiTS6ktXn!Iif$ftU%wb$6n+wHbd_3IeL+F5FQ5>~ z3R8+?Q-1obn~k~dosppNrYN~m!aBm}>~tw1Pf1;+a9U<`!eDI6huO=VHw&W{;eTHI z|DNWc90Nj_-Z#J16@H&qx+3xz-t})<_iK^$o>T`H+3W^;CC|Gdg0L|I&|v_+G^^76 zYQWszSyZBe6{H`RTH_|D>YrL#{5eO9=MAF~`KR5JLF3wo!!FtDwQixTSPSdd4g?^D zIIQUahh$KDt~-TW9{<4!Et}R_I0{FQ?HEIdX)Fy! zcPBPVyUY$FnCJAE)wug(rr2L6f6~sSS0BE*d0)OaLcKcaTI~^zhJww?&{4lzd$YBhGT8VFrsTl7X5D5PHA?+4 zVx1X4yUzfZ%ynb}vKr;)#4*F>TXgi<7ta1-1l;eV{4%_B133Lc_=ZF){CmTB)_Y6j z)p_12_+c}^+^1)7$fO0z{3PS3O1_ise*#zA{~NfD13jK$Ti|a%Qy_P%E}>JC6qALw zNPHsP$Zn6jIgOW(;fxP$aG|*=IPtGVLeHAjH6I3JqMELXeVo&RH>wvBzbHw+htutS zVSV#wKwL;=2Qp0iTvqT{&cU#+e{CKqHP7v1#Ix&OnkHXmbN4<6W2mf2>~yk}Sz$nY zbbMMrezT+dGFFmfKz_w{PoJk-n}T?V9>^-rosA$;PXxW5P7Myw3rNxHDoYNBpdaG> z-X|4~{s~XJ_*DnUL)uog51EJR+U7=w3p`*k>}k?K#(_*?>zUu8YYVp3hmT!O@U^z_ z@i=*&5ZCw&si9R zJSLcALF?yc6&`7_#95E7Fd?fp@kH|LE? z3ItItu$%oWL%h$k8ReF%&lxA$6%<#(P_y#ftH2bO53}0PdHm&USr2nYhg`t>{$s#zEB(LY4ymi;`N41lgp) zp5zp+Dc)HTYu0UtNVdik{kHmLtWQI~C2}?-tPj!M6t#tQQFn?@3S-;}zO#xS@mp<# z!H*wozE4MQHg0!h7LzXqs!KRLphOG8yyNpEAYz*g-Xt}g&dTccuf%^XxI{KbJ4cK~ zq4fRjrIK+op_F7ojs03OU|uMttl>O_L=Z&5yzH}|*r5=4x)seP)_1Drpu=r35!=oD zLqli$04Uqi+nty;^9MgRt}tjT`wNM;*&^7lq&?O2euz?A5<%T}!B2ngr5V)6s>$Y( zaN*}30hKDp@thELXaV>Zsn8pGZjx*=3-gp6Im?W{G=wzv4d?XSp!o;RRPuirZ&H9K zOY3uV`c7ju6%30s0abh<8!rzRVJmfpMTgM7(nm+!>vsn!>^yuOKl_9gR4D#D!9o-2 zpo+afg6G9kWQcXq9kiq1Etyy3q9!(#Rk`N{W_I$CAb{iLD(UKbcM>*XF7dRj%+0`t zUa|AR2P}D)ecnXxIXpCdy*ByR`}uoYI86e1cFtG@;>Loy9%&rNBthUszIvK1eFV>) zgClzcOHw>vqG0a|J>U=4t7F1I0;UqvmQkssr)+BX{E*U?XI1% z4)|>V9roCyK@u?2qcfEp8ME8C|YyK(L0D*r_G|s(HVCdm-jK@Lp zbEfJ$smD&bWSuy~!!jkOA6U)Kr7%a3Qclu9;zfme99ZSMW9Cl{Z^x6H{*xbuAGvwk zP2=2b3UQ6)LZ$B`gUr0Vcs;M6PSC#)UIy=r=|4ieMkL@B+N$r{b9uG?U1~&>E-FJg zmhF1>5>VL8V@L^ZKWJ4QK8z5xDP_D{`%O*NsJcJjD9CK{g+7apzE)KykST7d_MS+- zp#1AoJye?9PD5Z^wKfj{%D%gomf$&oH*9<7EKyjs*<6i8m&S~F^%GX&(^FN2O`K%L z-KgN$G8uFSguIWpn*m4qF7@DzcAd;@oq&V(6I^9z& zem&>3a8vT^wm$R;!~I)i{?k>ERn|pLVO(Z~74%7OMr`7Y80X{n+Hn>369zVA`FoK! zg{i$8oubV-5{}RIVS~Lqo{1HBAOYc&OWu3(j|4-?*jGgX!4nL}jlAqH%igz)zHiy< zxarlBZ=G(`*|}dch%Hq7|_|>1F-mg1t(%16#h3S0WGk zhgYf={7dz)`sY{tyh7KQ#6GW<{4Z-Vhriljt!x5X-QTePNLCm5)CS4OxF_^nu@Bz) zV9xBtDPP1p6E&Lve0@l-mp`*SU0Co0FGZ%K?oa!yP!uWT*IjMIKc9B!DO38iK%U6#IGRjmmBn8f5}2u__6DM! zLk2v+tk4yOQhKF8IQRl#ncLrLmswr zQS~)(c0on7!arTiMp&Q$lOW}KB$5q3)_yi$MgJM5yU!Zg0K6QCFygBN>`lx#zsGW< zPoaa3#WCeV)$dFHk3m~R+S#r{ppnTX;L-~L$@}BeQ6EmyDwBbXCsih(_pkP!_rHGi zgFjy4>f-D7M%24jGKQw|SJX}a>a4}Bj_Q*=uS2Uly~V!{a=fVZINhn=>8i*d6Od_(2ehFRADI5>&U=DKsPug%R{BMdyDMA0^h9&}ZV}47MXD`?UV~6O z9EkiLIn5k5@L;^tnrhq!OJY2|LQ?FNqM7Bw9;mW`nm700By|591t;_J9Q@SmQN6R@ zEDhV%N_y?x?W9mxne06wtD576X&LIRW@pbjD06@(1wtI&dx-GAHuLea&YL}7n37c967VqA?wt__=0E`$XTsZ!K|5`gM*H*Z$YF|@?JasUv-4j*neMIj^lo7 z!Q4FJGA0dO=aGC^T_L8NO8ku55v}8;!~Awb%5oD`7I#czfQ}h`4HFwQEnr}~a7#*i zI9qSwuU?;+%elvSN+J`P$CJ>`gmc%yAre*|XV~MDg&FQftHB@j;ZTxA=v9miO(2%N zEe@yA=uMZY=goxu0r4v7W#6pYD#>i+e@21&^56;Aeh9PXel7-}ZNuSwirq@XTSuEc z#MZ^fjL5GHx;(zI@70D*w$BUcc&DO%TC2QTs;m)HoL5Xm#4;XQ#`;bMB@ zMOwCxOL+g}=)dCsU!)r{Y@0iHOfs=R0mz%mi*qxd5|!iGE<}n`fEk); z^V+XVvlW}UDY&fF+6)i?7B&vLJesk4atV+~;cb?)PTF}uzNd7^Kko(9kd0eJW>OE66-kLUNlSf; z0*-y31N?kWSnBj}{(E~-lL28m7ph9mD!zn&pQ4bw#r9<9bPiu-wWIllA9f$N7a_oV|sy#Z7p zER~Vy5f$q#UAS5OrQ;?>k!V5YpYKW+yn`DrY(Vb@e4%sjZl#b8ET}aeE^LjpOz^0t z;#?`L);vFL{}3T{y2nS50-t2}ll|dyfEw%IRINe8ME{0L-2b8Mtb^KYyLI1EC;^JQ zg<=JYL-7E`i$jYRhvM!UDDDJGkruZ?@e~X0q)3rc9Et?@putbx?>p!0z0d5~Gv{9> zGt4~CbFX`?-@4Ydjy(u+rhd>e^xx4t+v=;he@E4KAqS+1K4(_|=S&3o0Q!q}#6GZ? zy^bE=y+#WxiT$#^1x?e40B8MjC0DR06F4JD`NlzSd1eeTaLU9NtHJUrBRW1bCM4EE z=4Ow`%NCjtj<#PXjtIEg5N$hf1brciXpQ2LW!0}>6_xyYW;Ge~`8vZ)H2PTD-$vlw z!GC_<=xpzQU%IKg7=DWXehDGj_vV>w3%~aC*qseK-|p<;R~-Kum{RG)*(9zP%hAB{ zflbAZM~iD)f=AbAMcwkld>BrYUlaDP@dnu}Ija5EGO;~H8 z1~&d`oWQ`n!QOEou=uxx_OR_b2&B_yBsn|G5k_Ed^iR;(X=1?;$w?p@{TF2ZC$XOU z=g;C41lS-Myynzenj4^U;P~2W zHIlNNoAmK-v@zC`ti;o?kGs3OW()^++P@T2`)~q(2<|R@hqXBJ?Mf~@>y`4ym&-_! zxhvg8eEE{2&DfaTu5`0IL<5y}57G_d%|TrRHfug&$6l~SH2df?vRjY|7e1XH(JPyA zA--7Uqr1uf3vL2W>eRdX;qWwz;)pyPkYElQ3=qu4+|{l{Bh}qZhUE7POTIp8BCPw0 z&A92DuNK4}aWT3CYt-gx{EV~{`{ui!7ec`(v35vzVv+2hi+@ ziM^*Yd-x-v&shG4CyOpwYAd+$kJ0Qm-}YZw`Q6bq!ot)!zZ7lInq`6B#-U#~H3&G< z_$(?2iN&+C6YYb0%?X3uUI5=6{cWF0SDvvbU(*qKQQBwWYn64*=9Rrfdv59+@w9hu zb)K>NjlU4}^1jJSMN3X~q9>nxzf-Q~uMjKKE88mf~+3z(#j!7;wn-fzs1o%5o4M|d~HMag5EU_T0C z(YtkrQQ@c6xXQCBV}}qope>kbP=a!%>EapK$q9w>oorzdU^cxjl4ra z|NeBv8^k5~G@rE3*PR9njxhh(nW@Q}FTb3nSAS?PcV3Ehi}Aib+c`DEv!lBFg3^#= zX5r%1hs91ltkfE;raAHISAC>413wV2Mai!%-fuCNEwEK?+RRV;T6nJ&AX?Mv^Iztj6^JrTUCj?;FkMoFNUSs8O~k4#GK#wC=+ELTrvVh zMF8RYszz@gGRp5^M=hNN{&|<(-sX;fui3&zkD>(Z@3Gyt%LJUdE7xKUVNU$O`ESh=p$y~$bVYU>OR#O znE(FiPm-0gm*`-t*2zi?+xZaT_AgfPPmVV#^?$O$|Js6rMEbLR&AH4n2Zj>Z4!PR^ zWe7=E7YD7bwNmmrnAerG9QNJZ>4Q6cAsa{FlC1SSWiXEL z^cgT$xKW0z{-CVsPxYsVPM%Ayh^Zj^ru*ky54*V9Nm(m&Dx`h@5jT=?}Ok&;A zn4NN(JmV?j$xf(&Tk>Y0mbJU(-4eRZ7{-iBIVB);>Bg*?u7W;0w2?*x(h9&s$UbEShcg|`mJr7KDU4U zCiBb;a@-R7qg>^j%D%zm*6&fqRH8_FTkQQQ_G%WGmaNSaIrskiW(Jth$qiPC>y^Vd zF|ZSkc)qNO{aFu)L095nV}_+%n3&)uQa&`)j3?D%L}Q>qk^54wS_g90La$qvY+!=v zl-;(qOp^&@k2HeWRDFgf<+;7Ra7Jl!CsfQ|hS2)$r)}su>3{MiydYkkGO*qYSHHGp zMxY6Xqz_a-@$t>&(Cj{bTQo%Dr-bB9f0{aX@v3?2p#yn{(A^+31F}8Tm|*4e>VNto zzqRE5^Mw9y-=$`f@bn&U`%W*jl(L9ViYD+!yxDf~!H%jNQ~OFJRIM~FuIp>Xl%G*!ICkk7pl~c@b>J;m*15j^D|C2VYa9j*Wymc z?NgqUO4t4IMFq7_Qoq1`_sze#Z>5{ZrDVy$ev(%hcRm(BRekMDHJj&rQ_===t-}B zp9PDISnV!0*Ui(|ZszPWQPIrr^z&racapNU_EtPfdtzMQjnP!2*!?Om^7M!-D!gBF zR^h#kOyqFyl~?HccfF(eQ__(X)z~j%Y(7$A&+|!@aH;3H%09QmnTVCIrcMW0?uEYl zGL^2v68tBRg`RYCE?B$b^3&~H42QMxt$^&5d?uZbP^;F!q8@8&uuv56xBh0J^=%O7 zaziP)oQ}tv!(erdm8DT?&SF^jDtc<)r*s{=nzQu8In8nOyA4%2(HFKE`Y}!uzhGyz zz5u3-Q+8)^_X~un{?$aPev$y;UaTO_az%2PNjpUAJTX=5PC~cR11o=EGqQKIVy7&G zo8OHg2bTu+gOKAP2%~LajPq@^2u>*1+@3WUf)X3jo+2N1)Vi-5meymq`2E}S&Cteu ze)HM8U-ch6>6lY;>c8IEN>eq$InWDM(n2Me(i}25@W)4Jy5>VqPqA75+l*>bhq7KG z9esTNK+SWnL+NS01qUf9M6KW}b7(tAx~dLLyY>9w5S2MJFpeI+h~NlKMGupsW|a*}XPjg>_8wNf}b zq?7kYbalBAWcj+noEBdbBJ@X-ej-kK6yC6+)i87CgQ6ZL#8^1-tAb&j%`j8RD`iJIe1yEb6 zMfOJ=8&Tbiq7i4YviE%s1;-htW$~927N6rkU9OT$!HX{;g2GD)+KuTd$XyEtmaG2w z8kJCapuX;K1FJ-v5BRqfB`b%dJZ-CSDRA`Yvsy+b>T~;44|ZXRM7y2lYz`*g9nWp2X8qo?K#R_(||X{(oPSeBBN6fxrESqTc%n{~M$xjxuGIzI(X8 zo0^8L?GH*hRCLF=zhJn_S!})JIwsEi8M4k_EM1ax7y4w=zmjRrw`GO#mpLg@socD7 z{*&6)nE19IRbgho9!|QpJ`GvIW3_hq^&WudqpeSVvt}9Lel}zc3JTVfI1gOa73{{? z`4GB3mz;!k`bPp_O>|&gvWSj%GnEUaV!aF(p(PPfv9|B^h{5tORL)M=viluh zH!l5{H-|H7WU1(efY2iEERix}f#Ys%!|Rb00U<*F`2<0Q&f2p!GXm9*LEQy(8CPP% zV~I31^@z{GKb%vP@birZ!cT8lc%tjI5K$&-D85FFai1od9A*M2(j({r_W$ut1TvMn ziYTGx0vPS7$^+D3HIVSNgv%$J@;hs-@oF-MHIqapIvpd33?EW`^k4S$eqSsU6b#?U>)Mv_PBJf0oRmkOr-`EMNAM+6p~FD z9_CNJUmS3iuaM}NSn*!nOk#hTp2}m8`S$GloTY{zopo8|B4O!r#n8`w3^w^<9~MpY z)XaFc)My9ZpY!(sq-cJ&!j7IGx3lis>d_~T?$z%TQ4K1Rl((SALu^`xx#ho(ds?lASE)3Fv9%odh=PB;@-;-Yji~%;sfe;)_x0lBDFdS0w*ziwKU^GVx(Q23#?G z1}u6B$cp}hME=$Kvdu%&kX^NRCgX<&|8%|v7{>mc#C)GX11o^{_4!_DV~}mGMyI!~ z(ezZ^)%F-{rJq0bl`TSIuyTQHz3j)+ z=M}00mxB$Qd9ak6?w4w3ho7ut>T%s~Vc8kIjoR2{wGJxHdu7nTp!8D<6sqKe!_b~B zJ78!V48aI`ntoRL2K~x#-I~j-Vdb@*ZwIEE2!#Y@9S+RC%hs+Rqn;$Bu9Ibp=~bC$ z29z5PJ()=$Eh))9*o;`(jG9{0Ngf)d`13rzGFWsG+qzEwM_++Xkx|n-jr1(LIM?t~ zj(587-qY^zu7TZ6a^hM2nHRn&gO?ULx2o6MNZqFzVCyem$>De5l`N*{nIkbNFioP> zjk$M&F`h@*lcNz*i6;FV*B|Q9lVCE%y6{jRy5ELb;YSatsB99n$80SgYD?|4?4YlW zuuM?vr9}lno7LDiarR(>13g6B%+TxUGR6$lK($W6;q~Cey{H$u_@6RAMvOi%2OcrJmDh3N>?{7 zH%D|1Ag5y8N-mNcNF2t~@i;?eamMpGZ#x}j`2qfRX2&B5>fENcG_#DM`b3UyFTdQr z`}Pq)iS0%_|Av5J`3&W7d{_DX%`#KsFTQ1_fY4@`Tr=J9k|zRU@yL4z&cV!8(hf;qQ71^TJm111(yMZy!EP@Lhp zk3lpN-zBmA=T>;|`1sBTy(xY)%Hiu1Zn&u%fAmYC%}^_4WBDF$`F)JKJu(kg(e-8u z>EI^S`Nr5P!l?_I<_^HD!Qs0$$dS%%th4Bb_zB7lATc3!{kXVhmdR(dh)8X%;Is+h zZi*w>aX;QDeWF2#!&ys;t)&C*Z={2Md;NAu6V9B-ap^`9ykg_!#n z;}I7U$6Nj~Q=!k>AXIG=_(NIR#xV%~7tL}!J&qQc>z;4c(rL%@-mWaNJp@G^rtohg z`*{q?gL_uXdqtVlYss5t-5x&);9)jE9z~_b<=;?qAUuB{fJ(@;r$PlLAhBAG?FrTI z9+mqD&Ulujl#_)^%}$VGHZZNLpk=L}Fv{Ulo*m)-X=4dLkhLaH#jnD_?W46G)FVU1 z!hD*pfP#CGr=p(8R$kJ^r24O?pTQ{QYL+;|p(IJ|2h?KOcb-(ACy?#;4gf0FWs7&n z7+dS3dN66`d7~r91qPLDL}KdQ(bW=p3bmf*gslE9wl`qAVb5R>((|j7|B#Jd?`Uq+ zE|LP-n;)u$=s)JA(c~Z)GC$btli$)TTjZlsr&&zYC2)LH>z|F{V5Z1ex_?UG*u~}i zqjJ8?bl)uDr*o-HWL(~_i0vdu&WlmesDHrNV4p6LKgbSPML$taX(VXk~hT%hWe&+P@&NG zZG=BhQ$nlU`NQ+z?w)BGKfh|F3+vgYkfg(hn68Gclc*LPh%bGVq(^WQxRZ{sF)hd& zIs=ym29sMSsT?a$9Qg((#VF$QS3X$5HdMa*T1b2#r!>Dic@-hj{CeMY;9Yy1`)d=2 zK-QSv%sdGiei74z&Zl?e%D%qcH+vVD`RJWNU!#S3V)G-EwErBrWK&9D zN?gglZl#~rgs*k{bR_aR+yLNqFobWq5*T|5Nu=BxysO_AdqmjJn!mxFu`)DGxN^t+ zdoYgNk0%n``FP8Oc_GWCzp|geiL-@VUqKUIY>M-;G2ij1JDD(KV5~3o?XOjjwL~M{ z*YTQF?A~+8&4Z?u+(SYpaeg4b`rGmHt0I(Lf8*<$duD_4fmg+^q!=iFVh{aFIp7bN z81o2uvv{MA=%C%RSebdef2s7})8qeJ>wHGS>(Gdf+WY=$>j5_&HU`2!*HCOB@CLp9 z5MiiTc4j;EJ=7YWfdo;*KX;wEhTLR@fg9joz5Pb-HG4qc{!in?)euvzS9;W`5VDmU zcsOHqpu`(zQTM%BAyh}^Biy(4K(8)?>w`uvzTaB*b1x&qaFxp5^44%H;0=TFd7>qen5{qs5FIB`B6DBJ?J?k5Swx8$C|U zrCS!M`{L}$oa57K-&!XKKK4@R7ZaZ*O>Vw&B4D1s*B!P??!itbpQd==>t9T%o~G>> z+|_=MSW6bPBN>k0>JWw9bVAHvL=o9_-l|dxiO+5{jsC);IeofJg8@lT@`^OyN=97V zJTr|ajSi-c+&)E&w_U1H>vK*A{l!|{$_f7&_|5WHD6U_~kWxi_miaM_y=IgjeD9L+ z_5{vvvG-W)ZzNim;re+-R|kj{V9B{G@PDz-Spr_`_le6BJ639JUt!`W>e|RicM0l>Dv(Lh{kF=7Tzkl zx)RABgG*>>Z}fLxwlH1oVzx15*ruKGb)eu_s0D8b)8)rkFA()EA2=7Oazk029EYjo z@9tc@^#t2 zNuMOD;Ttocq=X*~Q{Y;@8-hhT{-;L9Bwf?)u=_AS(CN2D%D*`V#)~)wl#Tsfe`U$z zCrVA9<<7Iqh;4u@c^y{tASWJb77su-o$rRB4oHj9lhk+gvo%q0$LPc+NZ-$j9?qGT zd7#PM+>z(%9yjd=GddM&>9)q;c8rClYPlMqiThu((e7#PJ>;)+^3Grm@y7p9$USiX z(-isVv%cXLXB>}DcrAE^q^F;FW+XCrIhM!?z1utAmDtDHnm&JWe^xH+RfZpa2Gv%) znfDn09T;UGGX>^%+pLst$`2MY&GaRA4ZITsrbRYSGi#%a5L|pFHudetJ$NC%1Tpek zY<&1@cmRD?*Q*^*{TlWrMPxofT}*-~Q2Hj097{0+|+bn01HocW~%x#)?MPRdQ^`TA#OuI~p$HJ+UU z7DOwO%$3Hft(eXVG(IOl)@f`{-OZk~SDUn!Bc#CBWx`&;89XLr31w^9XwPLV+96bg z)s^k`ZPRm5eJu@pUU+(j@POc6EHy!|s_DB$+^t0r+44^ph5KKkr5jxPZ4~9^;@&f!7jbBZ$`74{m>u zd5mb)X&S$g_+H)TwJqOVrBn%zT3T%P5B?1Dw|6dW+5ujxSe#=M5D${Y&`Z2|N3HHu z+lqnoPn!UT`!6(bGoO3f#PIvbF)kpMjpT;eTIlJR%n_E?Th^^(+mY5f{I4S`a|`ij zKRb)MgY5hCiuA^oT<>s~cpRgYmmjz&do8_c^1_nxz$MkBI`mz^rkp|-uho*m*_Sh; zl9O$r5w$f#i6%EMRu8Y2_%DfSa>m@3mr42kmhOw*@q$q=1xe0bcOYi#T)Z^iLZi(h z^sNr%I(Y=EkEHDVS>Ka8Jx-cE);>K&W>l;GQESHC)7V*z_Pbsi=0jw?+@BL6SLZ#5 z9LqMHt-y%}8)W#9?nbV2)EfL!Y7O}snaOzw&;Cu5Jl34ipVIKSJB4jp#{dgAA;6$9HfC-fHftgIx5W?zIxQrObn-5rHIoM&pSo(%KC zSu>0aFBiC#~R&ps?=&Yc)I<1x59nNd*(ZMeivjCZ3*lTz^8eo)q(cK z4oHJH8svFzr@||HxxLYjg@`Cxm###SzhzFDaPT#wQ}fQZtj`S71$pQVS%nt8QA5%t z2lh%()4S{QDPcxNnS(kWM9C6&)8a`5{X!8WIhkl9wPSaxqI8Iw^1!hAz;Kj*JzZ*! z;kuMz(=o&;e2w2~+WE9&!o6;c%L?pbKL(Dop2tQwEW)7W%aw+L-XVMtky3Xy{puk_v`qEhn@bSHs)ZTbg;}$`2>u#fQ^z)5Kgjk?!X@e5 z)cvBllVXh0&KM11Ys@~S#eYQp z`m+N?UfR2?b*kF$8S&imd0ExHck!V==ueaVdaE*9!67T!hDNLey!2svw9f|Se<#k0 z@MCSE_XS*_p49z7-M6>t$=C^&lCbmkW|xlka@WwMC^lMHItj{m-nWMVZ?2x(C-!yq zV=c0T-t>!1#A>EJ#OBuOqUE?pF=19e2=VmVh!P^~Z?q01o(&tt+6Ac>gegZ?_{OD? zM_YFqFZzYtV?5mIgIqeURbI7S1@#Si``k-@nKeW7g?iT%PT>s}{%#3hXHmObt;u($EXL+{xit<8lA)ux*hKS>e!@jE-tkvwjqyCEF{>C-AvyL^i z)d$}GX>ycu?w0L(Ckf=V+CC|NxJGGvN(S~~`{fAY!x%2_OMOt-HDPc}o+Ck5Aj+h^ zwe0Z=4+Y#<_~u-=+);yk_&5%`=gqM;S41)! zD{HD`fc`Mt;5QFIUvr)roAY?hd&1AV*R)^sszWkFh%RI%EkQ}%3xjEG{yEDxANQIiGnroC-3&IWS&0>Tq1m$>Zl%R?dX55X9v&Dli=4^F=A+LAP3gP>Q&&1O? zZxlb;{&~PX1^j-cCFrs@FP&0PFY~AgO@Si(#Pi_wY%G&}8olE9CooMSnXVFxCrvbq z#0fjsl|_%~7@w{_JrxQu{o*HOYdT+XjVUE{rRa>(vH=uz6HvtEi&CBw zWa}eh`1%YkURg1PRw8+$%`fY1X)&GKMw`b1#DN$*E3NU5 ztNqlZ9E55JU10iz-qzk;wEtOu5crpSHZ|Iq%&KGz8*aQTcMV)`&@gL|78y182f8wZ zTBD&WDeFAaB=B0&|N1UaE&JTocuKD`bu80N&JX^rT(Zm^roAfmOeg50k~JTL@iV^* zij}0{EQ?uTD3mnxO*>(3m)Tdzc=fa{-sVKN18%|EuJ4;n%FOZO9KwLhQMc|b^qywO zP`_l}cs$JQ@6V z(6N_RmvX)=#tXzp?jOY#pf*Ceog5gNl^oHLa*6brPp!HykK_aG7D@R;6 zQ$@kC`G(JlJCL%;j4qCUSd?mk-}wG{g4F&>3nQ*6Zve{U6-_4)8x{cl^WNBt z_8T}5Q+1$Wz}xqmOtl_0seM5J&-E+2h%(JS^!~qRo!4|;CL5oPWRv_ojHhY`mx}*3 z!9TVgcHKW@qC!j13zbLy&7Dke2~v4eCT^h=i9g-uqM{g;PY^{tuvuvK#MG-`W$9Wpu6q6FCsQ-42q)nV&EX zXTc!o5xD+9e-OWczPqQbr7m%#VCd6c$8-0CI~~enWeLV#t*1Y2){H4Un0vanCkjZh zE9#~j1{lMpjuqrMWNCnt8QN$4RZ*^sBpB{_uVaG0!1uy$XyhlNp2y9kK2?q|yv704Wi_-17x1-ARXV7a zDZPPvp^jI(nCqj8?`Rkq53Z_tu^1{nxM*tvHr==nQ)LdI3I2LPZkNk$OVUrRM7ou) zNX}GXH2TksIR>P35(wqS&Grh$Zj7L24u_+MiL|_jNs)m=UH+3F&W!;QAuWCQ*71Bi4x+82v37mT2iD7QTFov#%4`OOy zmv*A9{zSbxloRc{iS^wO3;w*z_3sVA3Ay?v5rwBO{h-eRBFUvUq{3)j z4#TdNoqKtK*yX{0!_UpYv69(_o6DgZ9#({gy?Y;Lewps)eNKo!9C=$eSI$kFEWt&5 z9_FHy{%XtJxw}sNz10v!Gl`$o9O4rM`3RQ$)>rT$+Jc(x@-83*Xo3z8Wn0!wNuS_M1FDsHB!(n0npUvj3sk z;?1%#w-PpTXBgl8E-@9Va)^6#kpjE=(TZGa4Sb};p_gFyv4W=+AFFalEJo&>N8zC% zsS8H87#3SY&|TQ>A$^Q0P0Ku9R5f5V9`X6_fneoI;y}nq7umsAjJFUozh?{F%@ha;2zU!YI8I( z2{hBo7LpQEkjJAUSXlbtOfQT(KEL(u`zLag`&US~!%ZOh3d13V))mnk*Vowd^k>r1-OjINlW3yf~-;!RBOcAvZk1s;^~U z#44ZgP!MuM7nmdgrWs>)7JZlE?KQHG-2`Hzft}E8?`d47ST3KP4|rO%U9y9hrtcR; znJs{!Nns8`Lb&MmQky->vrt|F(Ry)K)G(is`@NJgm-r=r^VtaKI~?4(5dNb)(XY_Z z>I@u6ONU8vAw+fY`c>HIRy+=`l5sT2e#S0^F9%w6OCqBlXmKLFu?F}=dpmCjYFh_f zOxCp1836&Z>zR+X5sSUtsiv}LX(9brA;e}gtgB1vH_*DF8dTcUM&z#peY!W?A6M^A zd)wajoB1M2?I&Q(y**vbInl8j7nXaMf=IVk#n3dvF^EjvjS3meBRDTMqResPY&UQm zbV!`Q;3di9By1q57-)y!i-`8>N|!^Up^X5uRcM*{GgAw^Y+D0u)c6KW(8_4VI_UTP zJd{5srcHkIz~9afNp3d}78g$8J2VN^Qx8u@ay&16Bbno{fRt)k_UCY^ykwVkagM#0 z%TpLxw&D-jVl=<8Gp3ZrTqxP`5VraLR3#p{Vx{hGt2zpU;mMi#xiV8~d<^@w8EVukh&+-ZBH&i_u9N^~n$P_@hi%vS&zG11VPFBStA_f1c8V~!8!BsbwIQ4ExB7Y_v_m!k>^&VV@1!9N$!9vN5H^=7TeAL z8#D@1_;>N%I>`e_n6fw?&2YWK)c$3}TzpjpV-)~Gt6by^WJwB1KTYko_#DhL3V>w6 zv2l=iv1(LF!ojgBs57X4;3uT_&6Vs6vknqcwONbZ%kTD+c2|XYEHl69J)D=meg5oM zdP{|q%6mQNJuQ~@uVGIUnm;)SeoNCO59FKFGFk45Il26$P2v#rf1b1+nMA`0=c0qM zmPZVyLT=1I8FeO!lK3L|LT@6TVZO%Hsb{nsUr~4cQUftmI+`SGLi4-;)#CzZK;LYx zOU4GKaDr+$eh(picq8kZ3G)c}qAl18o>UHkzYwo~fdj|M(LTouqGEPyu}L<&&)O~I#)nq>+MXC;Vrp;3XxU);_(UquNp zE$H;qCm2p=&F0&=~n2> zld(1_oKr6}Xvvr-S-(rC_8<5Xgc){iP?I$L!MHu0PdU8p1~X!waVPyR=N z(g52`yeYR&W>*k%hVI0iS~o(sz5=RGU!%6XEzRQWi!Z)pm_h-D-pOZnmFDuAw@mwSr3f?th4p2!yCKrZT=UMb# zrjL*-CxOB8 z-^!4kx5FqZmI3*pjAE_6;(Ga_Vk6=p{Xmd#3l-R=M*g92Y{GNM>6OzZJ59-Aq+$xv zA(FoXn^)?L;#H!fyKzGz{y-JZsvWZfF+*%ItSj(@$#RXD`~luefp*bhWff79wG^Nc z#?^xaM@Pc*{o{pS*7(Qk{l~d&2wg&c!1Pl@D%GVU;q~{SRUvLO_rP-7O?%?n9Wefu zm+3)Ou1RSqx_6pfy2ocWgP6|LBz{2@ppA(W5S8;3k4wZw2v8_#fm!fm^~otaGrOhK zD(yk$7Pw;H=X4Y20A(~`%z<0Uk^@OQ+*IF`Fyc9H zhaW3Gp&XEtm`3o25;+6B06KQ1;Bo0Op}jpH10^{|Q`*X!ZUQuh5ROm+O(!P>b6i^* zEzSsDY{w_ZT}60R_Rg6u&UD55bCq&4l3#M9lfK%an(L6#PYA!FGa4veFsI)GQ49Mt!O;+`-8sltt@hLB}

;b%q^oqVGsR^`=tKNU(^Y!2Lo zQ=SGClVeiomPN!H{KCDh)Wc*~XlPgL#*t;h3M-yff3r46>o=3Lf1mA5Sgm~hEXxAk zfx8oZnoM=5NL{*mb&1twLf#!sEA5f@8d7(6i~UoMMOn@GV{foQ-xsw|EWRYg%hG?e zTU{2^!ycd2hBEjUOS=A8P?L5XCT)c|;f=bkLQ#VypJ89ihqiX==QeKBux!qdx7P$u z2Nn-x@NG8-IkdHuY-N@ za$YB?TEBfgJV74Yua93)G!^A4MfcHn`m{an=5^}Q+sfBpdTB&wJVvQ=G{w7Hc4@qf zP`C<%v*9^EwC_BR%|s{`=_9f{L`&b@#@ge<26q4yk>z5_O0g+AGbz%;t~SR`w}pgrJI?NIG$?d&Pkl_2v09 zQ2W%zfR)Njse$6h*RAu%NleAhlgHs)%pdcs8YlCUd`6ht#veh(6VY7GhsI-Eq#sly z*#!D#5IvrB9PVu}01A7RUZ=JtsQE+~Kg6$c73UzcbfFYr2{2D^i{_tTXiA9o#?dx_ z2-ED3^By#7YRMrDo*A~P_k?$P@?%sZrhNTsCGVzVrcwwO zn$_8ezi5;ROt*hNAj)x}4B>=-3_kNi8jq(JYNk(MBP=_;5-`nL80LAUXK*MDUCxw^ z@MpH=G91m}jk9cxaF4^u+^d$ndMmRz0`PAUbc-PfosFBD%ulAn+eGFlz@Eb%2hkng z3F1$Qhqrh!1Y`sHaUR!1b7aczYn3*ZN^bcTaEf52Tt@n)51=!y%Er1D?*-8-6eE;Bxn5bNqz;^iwZ(QwSXGBa5uu*fy>wkhF1qT~nC0 zEqo_wOy*Bn4QZvHQO$v&$`Ix5@i*?^53~^tEtKxgM>65bcCYXtxRq3t_BcMj{j6QGPfJXT*3TS3bnue30i?!bu^K6d+jMz;hMRrPBJs^{etC1q^)9vUEA)?7f znls`RzC0t~Bz6JbW5Sz35C*M@61=x6DcWeBXpKmKc$Nr*m`EGF^W~<-E!KKp;*z?w zBMA-E<;|S(@)hN{(xx)66TD4??ddp><$%euo?n#ArWziAy2v^|@rRNaiPUJ_bgR=2 z+o~4Fr6S)dX4>9@t|j?g;n&u)u)FBgaDTKhlLy*v*ryy`IkHb(!Rd@wz+YK?Saf6s0Jc+JZsirEpKlJLv(XJ z{8%Wk8B!v)Iv;%*-UuCDjTqa|>*{;gp@}ZcyK-kp9tEO3g2IIiRM-*3A*O$HR3Ffe zD?KLy!J6h5UsUfK=st@-Hp2`_$iaK@dLH4~nXOQws8UYM2lV!;mwoP@LEQRe%q;iQ zKZ$El@wGu6zqiR9;JiCLq9)|ix>a7#Zuarw!qN$EjS$3GBs#cHgBoZm6NH^x)uO0o ztyJwFE!Td4?Aw7{Jp7mW2XPY>rx#`<%xmu8lRK*8Q5#T7C!OXxm%`S53F2=d?<&o zv9L>_ssK(_alSyCm*~YJIZmvlD1N0HJ%91?eJED-5FJBS#Jc=oMbYT@&*U-XLW1GV#)Qm|cKJtJm;LABM2)Z@77UQmvv(R2~Rp(Bx8ZJ`28mQS8tj!GUS z8$$LtCF)iEWU_LTQs>BI2fz_vzpZ&wD7mV&H(eFtYz9}OlBbnro*z$li;@Cl&q~P< zTiH?{*jGTBt&J*G15G^xHmRMP$M!z0#QG;FKT#WajYN9{q1&}d1wg{Q<#nKSvmXZx{6{ijV?G9uVD^DG{CUCwL8308O)10&GjG}e zke4*NrCwi3*w}sH?|SmUSCV)!c#)u$>}`;-B?})G*gT~>&Acn&zMNCKp3s8a!!}?7 z!bxa?Bl`CmxC&NE9(Byt$~FRrb2T~ZR;?xtlSF8=xkkrVUInG@kUEh&hb0Jz6AGUUrVPZ-Cm1T&*V@ke#?d}{6{@BwB6a{JV;0D zD9w2iqtb;J8+x!gu=u#|7wAE9XDWK|;~{TV!sfc@?m;`YOP!55Lh#=s zAsLp;YeaMukQal#YjfWf{Jj5WZ0nwg1yF><@%S_3s}86vUW_U(o({Zt_N5I6vQ^b9 zt*W<*Tr2VOpV!|u_(9aZ<CGK+(2M=wAK%2oN7z_?uY|!{c$@(;uOb9{K=^rfy&$0Dn;vvACShf?=n$j8 zXB}Y(ntmP?3^2>oq|G(Mpxe~0M=Wc}(p?vs_0XfwIXyNQ-S#9FhXNru{#3NiBqStc zTx(K~i4H!criMhSE_!gW_psw{CxD-;Sw3@uY%Dr_>~Eaq+1su{?^Qq}S|F{YO=U#^ z)$n$-R5R-%MEbd(8Bq(mNo0OAGRc?V{yWL}^xnK9%4=Wn(lGjtg{X+|x|IG%GbuDG z8h!P`6U>wE?S~t8qPOBUD&-!?hR^vItU~-2(K-~f)9oz(gcR^MGkU_k$*46ccs&2f zy^Ya6>A@E`H)JRJep}y+vV|T>d+|&fh&f<)qzc4PZbjia+SPwyW<5?NDnTy>W8*{s^HkMPn8LM|wuOwJ18O6RE#H$#l zto^=Nx~ne$xFjIQ&}MQ7*6V`2j;y-ri#tm93@mZx2{N~R{`T;1{O=<7t9D(7ioau< zpTRf5?)!Rxai&mMu|_lRBkx&@fDKXFf_a8C^avE-FbT`~ON~s`-|+niaKtie_^GhyJINn97+$N32BCu?xCe?V89@xOH_~$q(qt-kOpa_ zh7=G6h8hIUc;Dwd>;6AyotM02t+{^R>)M~a_X|*7E9)<3@BSwri%M)~w3+j+7;9dz z$L66H?ECf&CmtN~28`O$LcML*o(H`9E53esn37Z;7%5=W>0nF*>x?_N3gr(KEBS*xEw}UnW)eVStGU zAzhvZf?GzMWsO8^LX@ASd*TuCW5o_y%O(wzA-Nda-S>k#>&>B>nO;o>=V`My@~0S$CX=;FuQ4Usr&Rb?ZUf~W@+}O(gS7t zN{K(4C(iQjji<{IJfc6}HS86|yN@Tj;5!6DR9}5YZH7#3CvC#u2VVgF?zx`sDjt@| zA9Ci2=oc-0^3Y-PIf|;en2{`92!kH1 z2)(~kq;v;eek5t8Dae+5k$00^QSnegm2JEC5+4-zdZm4R@o+utkXW}}*mg}YdDcmZ z-Mp*2lj6oNbz!>?G>Ut0Q@7+xiQ9;mti1`no1^JL97S<_NZI{smyK)Mr>{->?xV!9 zisIrEq|AM}$U9X*?AFz)>&AzJyd9z{Fq0ZqOA$1?>rs&K>oW^BTu6X_|6aUA)MnN? zC#%=xEwgXc?H%7DPOLy+t3f=YYax;k zxNUuwp8Nm)fxmZdUY*%`q?4SguI7kGtBx`TiE)PTI&(GL60~QWGbW_HOYOF>Ep|Cm z!wg#|*fhwYI$}0=Oj>9-q?(Ek_J)p()&!utX=ytb%kUl37LJH1Q`Ce-QQ4EV7Zsy~ z?wWh!vQe?FbZuK+8ngK$&~~HrZLjXKU9$1-P?pePi}cZ231sKCcn>}w*@TccP%*n2 z`I?Yz{Ieq&py(K=Xn4y!##GyPaw4}DzxI0K?;mYnb(HH8t*EUOYLN$g8KlwItW|bI z5Qk*9wYTSXUH(Go@cLb91o=A+0U~;q#DVfGVoCvh_v8;3Tf}L)MvHUhrqOSqba}i$ z*wN7(sn;AmclR-$j3{MtvggF7Y2~C;H(afg`ThR)tBgWa4BuKVG%ib*O(N`F^w;dW zU4ID^cB92;7PrLvnp&)})0As8^*TwZ+8$2@OMCKuMm#nsko)hq*``RKYJu8t=)W)R zpH%w|>|4Mw;;ly4GH&*Mh;BB`;~l9j8WUcjjR<4d}09y%j!?nk3Zn18rn^4A}}1@ z&H_V~smtBM7V0?=sz<$`tf?#`oyBnpdx}NKx5jOtnRkWvR=sscS$Y(w1rA;61*K3Y zckHG*kcZ~ayLg3kiJFBUBObW0EYU*xsLrN{f+bAR4clsdRz%Mea8L~@R~ z9+R7sSU?ZnL+G%bz21K1*=N|3Uc3V9ZmU0d_RG{dv$etxf7R`zv`6LtkD1WcO zJZ)=VkEPzWOCJVww;wn(grc-=w!pw)-tje2kwksrR`C7}=ahu_UEl5H5hfB@QSiGH+ZRWITrjq+c z=j5j%*j23~IVSHi=34>r!XK0e2V)&(QK zo_ee2wbvevy{bj`lp9VsEn7mrTtFHnu=E_HOvO*u%yvxc$d$=V*XCos?pW8|DMDWe0h*}ODM$u2$Ie+Jz= zHGpdU4c51P$)r2Or65fIdA)3$M^0_OcLJo_aUu5+{sD11F5Je_gWA;F_6_j%Blj{) z((rSYTvv~o04b6RWv=Ovx}}(A+P6pp2}XF?K3Tk^DKWr<&+#{RjdV}60PiyzsH;;m zc1zS5C#9u7IgC$DN5W#|stt=+DS>b>O!Dzn@#h4CxR}P-h7RIh zW=_;9xR%YvHckptp~|@Dx}&LtEmujo9EPyLV#m{^r*>W+j5j^2GId>S`n=%sEzY=& z0y_>VUjv|KuFJeB=H|eM3^>@SzCI!{VGp{S{W7!Yu+d)mEIBpOr;3{;;^p^R3I=yirmdh{QrYs;?iJ02P-aFHn`rn1_cb%k z$x%^=cW|Z_yse`Ia{nj9w4(}^zBByE9PadO_tWSd`3_Oeg##@m;@=R&S zsFL+{%i~p%#Ls_S=Fx&VX52y1B&Hy6oT0Z8)!@{FuCr8%w>PmbelTPwa=r2W!<@FN zRZ!<+F?(tyj*c+&2J+%PZbXBExfUi|D!qHuj| z=JT6wJC2&?!)#ry{xke6&S7bqr+X@r27U2{jsy9AksvFR++G1TuMlgc@1WaZdDVaG zw(9@6Zqq(*G=j$@AO@KZ`pn}5`qpQ@9cpw&<4f94Y7B=u$rN%ZlfO=U+&gzO1q?R_ z-Y6fEVe(t=MEIGZCfeh7y=1xG>w~Y(ea8M$`R;w=EI}^r9r-NtfWR(f0O2LrJwLh9>*|9YMHjZVvE?`< zY4d8bg3{5&{^3yoS_>omJjG_7v&^uY3EJTU^vY``Ki{rVPn>NoL$x1V1m7rvp4U+t zj{JfloxS_$Lh|5MxI5nXcERC9J(TQEZWBF~vuBsOLY_|)LJ?&A#d-vRJI{BR)!I){ z_w@@5!4oZ~vqK}hVQF5zR0Ne~~r1o^4Ez>U(oLDb*pyoy6T33z= zd#-j!P!`SVcsf{cOB(KzcpycDMagz!hbz4oXqTy%#%G^FN+U$dHp*ADmdfDy)xF~v|^FHq97le zakYFt-;+^CfN=f(?tD1w&NDN!Te*QJy6IcdbSe&GuX0^|M@GzBIWAONxh_6sNmb6Z ztR4U9W|OwjI1b!iEiF#n9NOzNZq(I3N_Z;R^=$T*jEz3GO2c5cd0_uqvgQ?4p8x1~ z>T~c6!%)+oXAO5Ez*JjK>FO9+Rbp)FMGC1Zf=B6W%mbDeTl3H;R>z7qK-!_Okl1Wq z3N%$Ob`yD*Q~5i+&}XI9R819~K7ybidYqMuM8ZH7o^`7+eyQp@zM;Btjfo9-!I{4@ zqIQi7lk3I>J*iYH0r%szebVx?Q)7Sg?$?*dn^;7%D$Rc58&P=IQWco;589?1lPv+L zB#8+Byz@!pLsc!ljUG01y>*K-Nu@vRWTWu{-eEo=cH7X>>Y9R?=bdesD&dmUez`x= z%jbgM%gxr|kG^lW$a!!}rTahmae)g@Z9B;CA-PK|R_n)Gh%co=p5QmS`zz6|zd~bM zo|YTrRmlmwC0|=txnRP^~JR0TiTQ!Jk4uO}`NSOQ5_hrk?n>AG&rr zvXk4)UN8k#udR-EE&9$1cciWM?2X+OnW%t@wGCvyLi(AmeVkvMI4?Ue3FcVX7VUw! z6|E1#B*y*!2xGzvPQhyMznjQsiH-1yDp$U?t=fmk_G#$N=L6{4!Qps?4~ODbZQsk* zDm13Nc|vK=U;idRNin@BwKHKQw#o$1J!HXI8qvLu65g-xxH!*oXqR^v3e6T(9qZ}W zRX%1)VJx=n)(sf4d0C0f;#&VBFwP~arL4yG>*&Q2>oY2ndix|&PgwZ?wX9y9fk_PZ zm=!<=&uEEj8~gZiivK?jN~gF$fmbxEEV$)=m~-m6i{fxuS_0Y93qjm|HPS6zf+RfgFy0zmf)9Sqp3Q=WkU>=Q;^I1b<;OD@(Fvx0y2f=KjnXRRH11h6P0p-bzknD~u(wx?v# z4ROPq++r~&7IoU4!-Bs!HA`75wm>&}^zLVIQlyOCa8;EUL=sC2RO-J;WZl|OrDb1qHYCw*x9 z@HP(Y&m#j{D$&ZFY^Pxq^LPTPOD@Df67DH!d*u|~cIy#)Sv{5$a(!eoe$IA&8c|yN zq>zk5Y3%Mw?)mLD9^>b^fi2*T zXVvy=>6uAN=QQ*^Lqv7En?pWc-|k+lCe4|$Ys_?x_MTd+#HO7bOmg;zaF0O{W{Y>L zI7Sc6R$uEatG&7Ih%+M6~B81JsV7kJlqwn*!9Az--7h#tT9WO>X|AIf}{zQ>Vw6ZIVZn$ zh9g4mZ*|JBo?OAY_k~V?5k~y)JKx0$Nw{!B20Y3sg|%irG)uO5Q`+P`eF>&ZkvvX& zy8}i=v_Jhq|J~&?;`;Pl7(zs!T)aPRz!SdYNu9q>mu$lNd(GO&uIZD>&@V* zk^D}f-q|rD$Z3_!7GE?`K;D%YV8j}p_(g%vm*d8|1zZ0xqPf2gR=vAQDfL%S;dRV!~;#A!WQRX!qE1qiDm3fJ(r#VCC zaHVnSsDmjM8)aTj*`;U11c~yN|I^}%?FmAMT?)^Jq$nsXvV$7evMyOa)Wa;*Xt4GQ zCs6$swPLl0WzifbBv#O2IpPT7PQe~}ia}y8;y~i89k?f*q;F7e!b42|nCt>h*jph0 zV~{~^LsDu|GZTS0nOs(mPH-DdZ^Y0;}!`FyD?e5%MR)gj^x9ykv` zIfJ8_7RP~kNVq<6W<;H`r>#+-uYh&`gXgd?1N;N~V%@{rBV|N6(+Mc!3kS3H+? zC!N7RKCt4-vujCP+qi|D~Z>bw-a= z_`E32OE}NneR(I35O8aSX**WKTz01_?`f~Dxradj6Sli~Ez&!T0l$j39Q7Vm}sz`OVM`z<#Fxr`bVoB6ScnzYTDDAVIMqzx!YjoW!da3>j#!y8vDYtH# zyxT7utsSONMP+M%SYcI3I~1NL*xq^+EA!S~qV_{{?`={2_4i$<^hr)jZ7tJ{@5I&L z-m+Usma)S@D@$j^u>acz{og_oaoNY|J*Oqd@gO1k2{GOY`F8O76Nd>=9)dwJ%M$Ao zOQ7q9>o5Rxw;xhz_oH}?`QisxyR;$|FHyQS`UF4oYTdOQKH67~o}v-3?Q!V!QdK*F zYG??Q*lieXq_L*3&pW5Fro$$9Gv%CROpq|O-#Zh`%ii>Um79=-4{ppe-tvqLc zkcr?88S+OGh;d(wo%tv{8}`@Ht8W&KY&%xtkpevErZAvg>6?-3yN1qQeNR}}CKPVj z0)~IZRQf+y-|Z2Delj}#*~5l3MfLxo zrTyB4e3HAqhdXZwyAT$RW(RG1B2`?fHL~YdN-Wn{L1uO2zmOwp`<`%~`#d!E+$F9B zuU^LGI0qK~KeB>c>THcM&ew@c969-z5b{+upV8jR`igaYx~8h)z#UgJPQ*K2Mm*Hw z)JhZ?_u_eV*#U7~BXL52HGr;q!bY8E2GWtBgF6wpbP)M36phZ}7!}zj)p4~8HEOjL zQC@lbh%C1*O=isxYHYgrbPMC~gz!cP3*^0R3~dZ6h4W4-7u*tCCf3|;LyUCoJ+ts4 zFvI9^E>JaN^m6*dhFI{qX&1{43$#^+QQ$??*MTu(@%yST%kMJRKF9)6E=cp+6p79r ze1S#GpdLlBE2RsZ&%0zzB=}Bk$5MemtUI!W=KuMAZu9Ih5FWH7FgzK!TXY%c+i0&c z5AFxoixuJ{v@KISB`JU1OXr1bE1^^B0CLGnRyPQws=SlV`MRP!8X2U&(u_CbRILbDSj(3TEH?o-v0*dW`tWriWQ zyV(ch55^R5a|t!wQjbCJyl7hSv@QcQ@C}oZdGcRhpjL95aih}XdBf@kPE5bPIybWf z`&GG2vaF3Hzw%{V!PQe9t*1)dsGQ1*{=8$nuTNE2^6+Un4JFy907u)70Z~sfX)Ko+Cp}~;;o25@rTZXo z5Lk3-9kYDR`LL%Vs#{a_LFr)Nsqd)MNahJ|<IRJ}I!?}#HMj4yPFF4ZHB~figKxR6Sxg&bpZxmYE5;~&zjhzw_dxvs zo6222h;|9|C$awCET?oLysxpOEK|Wz-cJkOkFoDHl2>LJoS@OsPtvk-pyzSum4s~Q zly}Gx#6u9g-UB)tlq|9B6H`FnaruqMV)UF(G8O$;ClLn7;bgZQusuJ2+E7!DIEnL%Gfn_~i66VBp{4zR9{W%A2M3U=Lb=Qt4>*-1kf?K#2NVH6c`NPmg@S zJZW31lNdys*Fa*(REv1Rr#Hdptx!1lJl1QTZCots^BV~yDn50*!;VCeUKBY+Sj9lR zpM%?3Esi@8W&S}ZbRz}Set8yJzTyA(+XWpa?;Gu}_fgT}4Kr&KuTEWU8}WXf;7gN! z+raHVG0%3Mw$T3~V;n#WgFwMT01=D(z(-fPdq)GJ$ze0X?Qgyk(B(Rg@1O1240P<1@gqnsfb@j+qCiRg3Nxh>zthdM;U}iXm*u8{d89HdpiwGQhsx@TyQ2{c!rF1fur_JR ztGo7y!AVS83{`MXuQLKEOg9KST&i z@=Oy>g4&)lh7~{zJ6UPb1^$>Z$jr96GP;lM69?9r9hPg9cD=?d3FnzxCzr#$o)*UM z-BQ*?V0m=Pyb=0Fx^?}2fQFT&FB}Um6j=FY7CG&gGJe zl?NR11G}$+)QWwIT{|t~mRu~CZ)*PowKl?xn42R)hap$hdPVJpP^zOsT#fNZuhhWS zG4!k_;evMzn|BMPrCf~(nO(kDPP6Y+_FS8(bS-0w9b;J-$q!zk7S{s+o%gXx#I1LjLnPV$Iq%qsOS#Z6A}eEWNmJ>d4Y;o#rj zkNGI|CJYO83CC7_d(9fiPB=-`E?R!Qcx%}yUpv}?Z>DjM)J2Gg$m*G7LRERTbQ!AH zJEz2nv(J8!b6%DoQX2uOJjJPcnbrCa)Hh;U@DKH->LQa$n21V{!7oQ7AXNz;*{__2 zGHZhx9!#w<>((%H?WU^EBnE!BI^p!K#pZ|Zd zlNF!P&)g?C|Jq6iu?c68w&6&J-SB3}x{7{DG|*TW_toK)qqQhQ@;s4oo0HTSg17a> zG4}}|xOi~72nyw6JCv1k{QIF}ha6sOFR}!xMr4xsSnKzP+!tE5TXVRyumLq}Ir(r- zPO=bc66obfq(!BNOqF=tM?8PH5_SLiSC7P`I-f?5%$N)F%eyqR$#Wkx91Vvw&MrO* z=1S2?CmO1q{Z!M>F;7}UrJ%zR+BDlJAfP*6A-(dmc5)8VP7NH% zx__#PgPPj_z&abbTlp&TX)5P2RWK+3q9Tiw6&>KiN7s7+#`ORXwA zpAV|wj<3k{S$(_bEtD@p$mYjiQo~V;q^QpNJIcBp58*7FW#{=46HW_OOSBOxzxzRP z0+pSKl(pVnD3+?9sBhL}#BAB6+Bj`#*tXW0zDdF+F};6iLOGZLke$P_=WpSDtEP4|AULoi&CH)|4WOxP#g=M;$O*hgHRqIYaESLF(gQFj5`UmY}ONnu#UQ! z2Y-=-UpDf!a8-{>!jS~b1P*b!tf6%<%bCiwQB+4lAZz<>u0E#hM25b^aE9A_4Qx-Q zN~W4jWPy{a;*^FVqPXmh>Y;EPdha`)P-GpatLT+QS4~as2JOuuwtz-Zi_`4a(AE!BcP2v<=;7 z7P4eJO{a?4W z9Xc*Pza;c-rb0}s8lbVI!uwr{;d7^8t9(h8yb6o4V0`MJX_Y#ivrB@5n8X^*@$V7! zm)ZEV_k8TmrNSF8!rnZ(pzQAtKMEniv=}0weh*I_{~fbm7X~8t;QJ13h{tJ0 zS-Xz4V$uZ#|K~&S*UWpq_1@A;PJaLyEN4g~@I! zPRO+Ymzrlh@q5Tj&4lNjoLk(7RsI}csEjiuTN+EOHn+D2>!fyt{lfU}dNc7niZoM} zn<|&iKNAeRHznX`pVIgsL|@Twa?5VGPH5oKm?qt&Lr$S0;YSpLH&~0`A-0T~0}#yu zLGlC-%Ma6TQZlDJKvvk#49GZk%Hj7`(%X+W(zd@kQ^Y!UB;vHK_4y^kBUsYnPvia^ zu#?<-eUS`LankqnrFH?}N!y`JXzG#CgxQYD<`eRQ3!1{wTlQNhgs@Q1BJnYy$dT)y z*^Y7D-Sbh~H0{)mzMOhauD}he_8gm+9TxKgIXUrYi(F=qG(&EPW{z^lomRSS2o!As z%Kb*bk=kk8KxF&lc`4Vb|NPK6pEqxz;9nv`9Tv002>xKc1*XqxS3R;X`0dB`(@4*h zpAB4pZISj@1`Pa)t8|H~{Hy$~mB?_zTO+Y`Wi7K*Z0BjCO){L0t>Q#!J0kk5m29HK zkpUoKlbU!;tTl*;iU#)&0bOhQdz4bNSk6&z`GROG_J*+c;CET7{tS`CY;hvq_t!(!_Fs#~0t zn<^kqSFptMyF;yGH%B=uA;eq6JLd2V_)Sjmtab1;Yo$#{R$Y1qd>jtx0y>A}$$35n zTp{LI$RfS~kV)uqmBshoxPdjMay4S{*2*ax=u3{7lY*lgYC*xU+dtn9P0y;wn&z~z zF1Twx5I1EFcgOBDmDLK&tOb5PlwOv`KA+xxeeKj<-P;B$I!KI*D^b19n|{%>*hwN9 zqnZ=kwu~e1vNSIqM@kgY5A*gJ8-0GiHJfY7`X^t%w7@qgJF?OAYEt?X*WC~qc&WNi zIb2soL>cj&8DiVP#(jE`wEY$r_C@gM0O7D5tP$ztKoYL_k!|4@eVksox2l<3Zvj_w!b% zhF)cMDJNzvwZE03&Kt`3xz{V}Y^+x-*svR(MT@~!hJXB~!04%7dW8Fh5r3;AToz&o z`*z{xPxh{3j;5dt<>U2TaOvj}P5ZZ!6uNyM*IPZ;lk+HhMoQlTii>*2s;fZc<+d(p z+a|uaE^mB$dP4B?D%8K)%4e>1xkei?L719$RmsnS{6&0%f$7`e|E-(73goMjrKaK> z+T;ZA=EzPJiTqEj@z31S4Cmv1bV8^OTW0dUeM6=~F|!-)9vo%D@zpD>Z%gPnUWC1McUPxKl5i>^T@!ocHo*Eio~3s(6Zpye zY0@w-etiQ#KLq8`S2As-JR+I5d*mvRf)W7Qt%Z+C#+vYNm@&C!*e(5K? zMK$(t;v#@v|55MKu0oF3fs3BaOp;Zj;q9F#M4ib?H{QjEnDe8<)>Iq{$cJ^5P(9Bd zdkYZ3QY*W3MCZmH8~@d1eNSGL^sx-NdKz6O8L=hl*l{Mc1!IohCwUEoILMhGht+R0 zPbQRtX|&2CQ!=N(83$L)@+dOQs8w=JE8B!nlyVzmwPtO8?a#7i4$_$_WbC)CTJ_4F zudWg}!vM|q6sEGV{Y|L&tw=x~nkIDkFTwW{rmAyn;Kj}2 zo?5|R#{91|)~QWp{@td#=g$L%t*RLBgh;6zMRpfn4vhzHX+wh$N>JY|OWZgRw-L06 zP2VLe|GxPTS=vzwW3UmjNkJws6?bzKjDz?wEu?U7KdY~AI61`}95R_{(pts^`w}%v zpXsxErNMhW(Lf!KFe)C}MJ~}MJ|2hXr4}Flen{29z3u$}`4;%(tdvdI7-saZJFoxN zBRK^ojA@eKRaftB#r`2m4HoS|X`gU!KA1}3CFJ>DKu`OEqD@Ca2#9|ibtuH!hw1=t znW}?%TToe>iiY^jZFYbY3)``bDM`a-WW<6`)q#xNI@ptVK;{FN&qPBWasJM0AGjsO zZ{kPH_s&Ulpf|(;P<fTqP)c=-@V`tfJLV~Sh8f2 z1K_G#ZWq4U)pWk)&MCHmE8`$pG^wi8>8KLK*Tt_fULvM26~qiM{| zV;-g-E-ns4NNLrmiRAT~boa`6EG^ao{7>r$-M$gM{ctwm%XiIg1Yhy{&3>7k_Sil0 z?x*>M^scG;AOT7u`Zs*Ab7unUZFU&7L)aSYX zPC1d9_MA@FyfJPcxz|kovj6!p%>%h~i_hQxr_-B*+>%#s<$L;_iGwpA^#lX9F(OLB)G%W1Nb??`bQeoN-;iT{6 zNHiTaMAbIPY+tXw*C|k>nEz<1x%$m6!^SpQ<{t2)ligK$R#72jRdYRr|R2Dp{J-~)$G|}F+Lwpe3pnQbfzdL1o z{QJHmW#LP=UZmZ6Qf7_<#;G0Xz`R^2#UTCuaZlq%w;UxWMp7+$houbB^0b1qTu7=U zB%B6e7>OTS85Ps9YrEbLBZMkkOSiv4145m|G`8EPUj*4~mpVcDqcTI0E2#dx32?B2 zB0~*gN%Df#jUH zaWsuq=YtM)_&&~#8zv1Hd!CMz$}UmAdGYn#VMA?Htjo41Vrue?j&ITTA5!(Ef#e@y zr99Oag=WNrY=uw4gTX`aS6Rf~tSK%0X%lj4 zk>qk&oC)2>_!8nQVmRPhSfk_O0g0A}KE25+x~PbJIr;YrJ-8T5$DwcI_nQb=;}G2D zHPdZ1mn%H~Ac?$w_gO&-rhiz~Kda(@?{+fPQ&MUQJ<)CZ0W409vy*39#g#70G#$nS zF9@hZi#FfTEE$VJl$EbWiH~!TQUJP)I`M9zyF@tXVX_Y1l^_|9Y!ky7DDYbO?sJQl zh%NG9xLmm}R>7)o(xVS{nn;3Ok)Mf#2)IEipeO>(C4mpP^l9PXCEr9mK9IAr*E~1^ zNVH%?peZT82s@ zL?@9MmUU}e^h%erdMxrd2lBC-Vb8A!qK{@Dzqcm|#_~OcSmTK{)s7LK$Qn&b-%)rk z>cUC>s>xy?^8n`3REOIph_SeVE?Sg&xF_&8_tX>LRqGjLH zkZqVqgrf$#4bRUMIoM`3s=RgM4#-=McDThz;FP zz@eKE-+!!DJ!A=^9tF$ndOS9af;8EBTb+pvD{;W*y_W0PEuF$9B@KI7uOBPDU-@zo zk83x45-28AQag4w{Y|0J{%fofm{^FkBGII(*_{{$c#2 zm5d-b1?RO0e>>bP?D}4(Nb1dvJe6+YJ)7*7rz5q-Tw}ij2$z1SY+gK4{VHtIugi2+ zj}}(3GO5k)XpxNnOsj1!ekLxB8{f%7xK4c%doJf) zk?zLH#*z4@d@Bi-@>=3ev;Ab;pia@d^!A_ZIPLNw;)91HT=e1AfCUi)um4kSDXlG@ z2uC94^!(`3!Tjq7lv4t*-VKu8%y){6bVyj&1vjsej51j*d=LpTzBwYNhYhN(U4S;y zMl@#z^yv*m`(PiZGUS{TrTELa%@)L1-$g6LPNG9^W!llY!hVUP5C6mk4CgDVze(x& zsZXCiq%mrQH)OSe8AV_^q%&_P$=grbH>iXWT|)knp~s@_KtU=Cbwnw&%X~N@5Kq^J zL*k0g_@_6X-xVB*=|-UkciaZ@BuSnK7^;r;TaY5|t`z`yUpTS3JicCoJIGYeo2fM8+DDcW3^sF7vaPu>{ zXq#~hNr8)}`mDkt+HpA)gdkMeij2j%o+GVWoAuTd`67nDr1ys}1t&(xO~y`_wH&rXgJi+g{qpzi)qRlX*uaZm+yT zwNLN7>%{w>a=!*ghVe#S`c8M)p?#-Yb=HS0UjpLE&{o}*P!C5|2hK>=(^t<|v*MtQ zo>OXKj+x9e1kK3!wVF7|B^u6@8Q@3;br9KeO<66E2JDM9c-AA|q_hl9my+hyrk3{? z+LMR26m$RCJy}!%6>HZ2**#z6XzxNOHe{-$7hLPDROG4-(xhhA4#l=;3TalUduU40 zIpBYwR>~FY77cbhz1Tn<+(SxnoP%RTqiNtct3upqiy>E!*buQ7&hxyGeig@wV={L1 z@CAA}0CbVm;neBl_dG2g8>tEQU}4EOm|>BHe~3sBrdMnz$Iv!Tkw7X=I!?6O@J`>! z$cZl7j0-y~I&hxzEE42 z9vgNh19n65s%7&O8LDWS)j+kNa;`wRkAIK`8ADHA^Ly}g;jGp5Y`=j3~J*6DPr0JHBEQB8wrdyo}Jwq-iq9?nrMi}Pt-J8)o2Z4rjPXtUrcCZ-{SsE&jTG7ofPl08y%+ka}Zj|DbX-Lc^l)v zAfAdBoL{qb%KmhJ2tl6B;IrWLq~yo+u(FyY9xzd$E-L}LzR>tdN#@v3%Z@L<<{{ZF z)4x;K5<4|jz70z%DW&1pzo_Wu1sY~=mIgn#*$<0u(q==%^W(pDz2X9?yv*`fDxcnh z=(+eFz5OxVyg1ZnS|e0w#kno|$8`Jkl%Ts&O;B$8@A++E*1QJnaJ8L z=}#Y1N`(<({o$3x>W_u5r#|ML_RZ)DfMypIsQ$isl>B{4I5YWk;%4LPh|tU`P5KK? zGupEY4u`&$>))X$s80dopN8~+l(48D|676Ol0u7m{S(pe6HDRCSu zvE`0n+E;?M;i%2jXN}?Z?w@|wfj}~Np3i@!m|ammL}2vGALpc34_f4arL0GO46!_m zgJlv9FdNgq4B_443XAhd+~$oiCvv7V=-p67Wy-qoOHDbiezm^_dJNl@kL0Jgz2@f$ zTyms`>8Q_SJT0dxDB1Vda^a173Ls5%hKzo|D}OxL0~-wYc)(-;*-{PKI9{=8bs)ZMMva%HMPoy*CG}j9(l0M@5OE!BGEr;VqXyRjJ9(qIIJxRJ-{JP*?%p-fV1$KhTp-YLJ`mj|rq)5lbo-|!6QqZQv96iN7It;+Bk-#g}a0&SNdmvdK>g@ z zZE8t`TqhfIL!*`pgeH<|f-MSW|9WTs%bgfm|LXqczh>9J+FhW}Z61QW)n&iGl)Si_ za^UDuRGvz&Gw6LtfhOjEk$Tof2`A|nq`mNV7np)u1GPa0Ane3tmY93Dtqd6BEbRi;XNB2zw*p=0}`&1$jE^B2y-nuBDP z8Fx@#Fser0_!L=kC|x0Z*DhBt{5>p+W+hhykmqB&?pEhT(oDN~zDHoYh|wU(?F||p z^?}8O0M}^X;IS{#&2=a+vl)S?=QBcmJ8?yV5RceyM(hB!_hu@*fAOQ7VIHwf9!0+B zwo*fEvDj5lL^=m*!@M4VT2lzeOlUKZms1srG-=yucj6K;tP`V}cTzo1^1px=e@32u z9SLoR%V)JG60cYwPSkGMqi~W1I|K`<#zi*S)Y{ZMD)R_&>oc+W!e=d7AX{6T^M96tHRAte`Q{%Ql`|My{?K!`>gIFVPfgWczqai>Hba{}z^q7%hS&^Gt8 zexdF6;fDZOM85sUEOthv1;JZz>-)YcIPp|6Y(=k!Iu_5id}P z2tCqE!*0x(i9RM2dEOC@9LRoV>=B;-eE!Ytp-87kzn0$j7AWBzNbkC2$S}R**nrmW zIk$nrS5<&A1Gdam49z7jGA=f^_v9z4X&yHNT{f)d8F}5!0aA%hJnmLm}i!PnG6l8rS zD6F+Mz_S4te)#8ul_PxgDg0`bU4g-Z&Lk5U#O|jJ>-$TCI@-!W=O{yIQ?y4Po*m(B zz(-ZPF9ICX3}3hOZ5QtfvVa-lpYX4p+~n%8WhW%ly?<07BnXfqftUzDCL2FO4L$fP zAFB_xkPowFrM06QGL>!u=_ye`a$1HG2=ZP3nH&dtePOMefcc_Je&^8~IA*Ya0Fa#= zqpEIq86z&e0x9lyUsM(aE8YR&`)+8g#$JvI3l9q z4!lA zE1>)?G@*>*W`}b7I7{^HJMK-smC~X7!)ellMijh1;E;%j^$Y?HPAs`5bFX>0?jx&XYygpC4n$KT()oOGR{7Z;Y~u2)~;WS ztS7F2;V!K`EjKJ7G>$vYfc4C`s7^~=aHf(Ynt0F8Hrsum%w^tJZ(QxDC!&W|jeB8F zZa20mP7L$tR&-mT!f*!I!+ZdrJc_qOXt7}(0MT$FHILLgk7k`<1gh;bJFf!+6#8>^ zUKiyOxV9JKvH%!YIFJymOMWBjtB!3PXrD8h(FHldgnVb2MPmizKTGtj>lB@}ER;Zu z2F=N-RLwJ9)9u%LB8JQrg4!Rr>Rt4sadK&$XOlLNF`eu{-VzRG=DnU0xRnDP5Ac2x zM?sc5Z?C;Umm9BtNL-DHF%|4Af4{0dXJZ;%RpatVMIn8;mK@mPVqs~JzK({GM9xU_ z5xMfH1%HsjlZ<*}Ea*!uEbWw80Og>9xw^&b>Yf(Hs~hKa8m{#*t>3xT$4$isKzt#AYY+=fQM^1XB!A?C?y7k6k5+kV`Frdd zhc>5*5And9!khmWS?3rX=NoSQw6Qa>&BkbK+YK7qwrw|VtR`t}8xv1s+qU)2|9m^= z{XAtA}OxbsUi{cdwNk)nlz9JrEO=e%ie(x?cZ&Z0dmdA9c1 zw)W}zzh&7l@h~#pZ^U%lcC04KD1Yu0q)q}E`rDoF~7k>$qFTNj_TnW@|@)Unb^aZc~ zDmFyYdA-9ezfniMr?9fK`kl#7;POGT55bb@HZSePO^M;-Y@>aao0OXTjdVZ$l`gFs*Gfl=&yLj~Sz`P!f|tR? zhD=oy^A%q$cE?FVR$@0MQHTk(&BQtJ;U^3mx8km|3U?QrOZ}mt#)IwN#E9nQTb7_J z?{E)4Hnd57B9AXM0u7GQ$q0iyCP}i|=9Akn5sAY--`Sl>4U}279}p`Xyf2hAe}OVJ zk4rz-GF2oBiM`%UVzvItduS&C46Xvdy$Eu@t;C}YZT`h`5^!GF%A7FE;N!-Crr6_; zn;a~T;=$!H!+x3cL*e+SVqx_8k3o{P?wz`R5;Ep$qk=)ETuQRj#~>FEu~t zAw2eXfxexsj(FaYpi)Gf0>5k3ABUsA=E>{me}AISh57vE6uwW2P;L(|Th0Gh% zitWB#$bX%CZmpXvij0gE%YGY?MT!wCT7u($98|OP(4-$+?D@iI91I}vgWWMM=Klt` zz8RpP{^_4GIEq>#UZ*4@s^!}GbDpc*Oy}Oe2kb!jJSwWnyNla56asy5yw$BIpel@Zr< zwh5KX1|;1KFzUZaa#Y>2_s!)=oxHG04|Mz&=KzPp8Npr~ZWa*S*2ynGKi+Lz!tw%B zk@exJ2_wZw(NWAl#Q|7RUhv_U%oXnoSWgxd9O0)Zn@xc$fQD}3KOD8sdMFayMSoc_M6 zReK5LuA3n%WL`nswBC9$5#|NO@BKrKn&KZ{ruu7+*Z*{(-?Yvnu|O|yhmHS$W^QGH zB15lDm_1xGKHx*x)Rn@-b4CO3=y8)~a<)*h5P*~*q~Wjvr5x>~O6J`9X+A1-5kuBw zMDQz$z7peDfj;BFqKVXCxvZ%&p{|xV%+#M+;=bR^Eb$v+S1a5W3KMfOv|$6s$;K!j zBG5;0OMl1wHE3=~PrVb(Y6V{nxc6#HCIW}j~@eN9F>b#}@lJqwc|BT$Nkj?*AcA(%G zf34;lB=lwQaN{H!{Eli|tWV-4hg1W5X>OL(W5IIq3Wq~XSt1C2HIaun0_>H<$w?g?G3>=oh;7vR?$xbtt0mF9 z!QWy!W^vnG9Y>-z~oo48%m< za$IdZ2Qm*+-Wxb+vshPv!oFkm2|^(}yctmCF-BslAojAAN#b`iLN;KW z)IwR*QR+LH_knM$y;okL&Iits3Yym1Zdk0xG|f3OCQ@=8t^hQ<>Dr(8tY{gN85VC_ zK^Udng!IyY$O|unt>u2`6F+y*ekZfrX5X#X<@R!?$F#sJ(cR?B=aLViaK~Tz&(9x! z&ecmL3zR8y`2(1l<7a2wX_?4GkIMxTB!#0 zxTl^!e5)Mnx1ZiV8{8izYHbITA!P+=-7ZBfkAJ@Xr3xl1mG4aeW`~g7--ML3D+a{_ z=0jMk?P-S>Se0Ynq?1Tk2k2pqUDsLEQFt{35^T!E^}GVIIh*xUN!0YiRIq;FYO9o* zihD6irfHhkdO<6ukZ_vdTeB8+%R;}Em2D;Dl9dti!hPR|OzjrA5xa1Z5irV~tNQy3 zkPm=xL2GN z1!KU#E*}DpY>K^Uh#IbmS$$Vu>f(R@8kS_y&i|00EBc{3E(8GybE76Q$a z7HLH+31&@)xMUc!nUY#ki6!IccYxTdOv7k5I3u_qI0ZO&xVpPF^l-F4DmCG16BJ9+ z|6*TwYM?mg6a?f=^wvpEEPUpa2(-eLBQAZ-1tnUP-Wy|h@7T}tkDNO(pz8Vaw8PD; zU@sff@0W>J&3URNRzS^}Q}9pS&AJkCh+mT3euz(2ZS zvU@GD+l*qGg&=<-(&1T{8~;#cwlmaT4_KM-#=oh1|NWa6OFQ>)53tAjyDHr4 zlVaNTQzb*HjNM^_-|dnp=Yb^3dOXIhiHqd^xEDX*cBKb33x!Y}3A&@?ty|&A67(8j zm~H%hNqRn~48-E~}ty@G! z`>T+W9pUiGwzUU?+aIMG6zt`5w=|}8x&8u$GL}ee+TSO@-Rf3)^VjEai1Ow0iNEsA zvEg^AUKZzwU)GKD;FOf+vk-4=YLdVxmp#5ghDX-GD1=3nHj)<1Bo8*0z$ zb=qlbFqt@0;WxkeMi^`UdLHYFYeR>&{S6+;_2c((@Ui+P@!7o2EO(RjH=cJceok@D zcICBuW(di9#%@{rMpXTuvcUCw;L&Q#d41r6vm9fpGymQWg%I*wMelyM9vj0<{@hBF zPmQZy(^Fd~+}hndLH~VUr{Hn2AdhZwefw9p)B!*P)m9#X=++BMY?w+b!TVLln`0I~ z91pVRq;_rdV$w#)bk?{=VcG{s6c>9x5%mV#P-sdH&sw2^u z=Q4W?NZbIC4w~qc$+*hZm`+ec>}pgjsH*cic0sbqZo!h3%-WsY2)U3wG1*@#sTP>% zJY4Mi)k}%cOB0F50!mv7_qaAloi@_67E^(1TZw#IE@m(B3LDK`)<9QAe4S3*FZ0)v z3yIu|5$X)Fm66C|G>`G8r4U*uHAm*=o!F$(!kwpYrWAUPzY7t{ zV1|YRW7{@Q#Qt4K4T>cRwhELyu9W6zGZRF9QgE7Y3DrD#!a#6GH^0esjaqL; zBdiYPwO}E0!EPYDxkwgVvDJo}fR-P3>NuOtqhoh25ynfmAi>sFX}37~(SpxjZ^Od) zj#({VtqPH#<4{@(|B#z_Sek;iMVFs``0Sfd#s{XB5Vyc6O;rl)t!sVtyW1&}pXC1& zN*okB#@BQO^~YVXsu@*DS}?YPSHnbc@tbb856WSqP{`=D+f&$_4mcvr(yitysZn-5 z%GJCXeQie^+q$JnXdr|SM6T%D`U@zttXicstXaSO19Uf%Ut2MxSzXm=-z{ zqU#FaCs72yNd@U^Ji5UD(HBLd_J>M}D8S&Wr0^$1xcnYt1FIEEG=nk5b`@;F;5 z?U3;FB~+#{Y=4>f6`ZWhf=ks(ca#*v?`~kYU7`--<&Y=;H*;RkKVHxH#|haPSp~-k zWBlZW0mSB88fPn&Zlu$gdVjS2U%h+zs*(&P#(nWR%_SKElPV(#~^~e znqM{7XAuu+S7M)LB(MVH6PVOWznpVB$h7!dRooco&EpPbN@&t7!r>##lPNu*BGf8PJJ--4@&>>ucP>?vdGiCg|ot z-!|KN8T3^MkoZT^O9ddB8B_w(&DMIp-Q3sLkoj!NE#16g-@Sh9x7zHQ+mgntwh+Xw zb)*i^${kd_6JR1yM);T=8{RocZzps#?~;aSC1!3jo~=@tNgqCRh0t8;g!e&46r9PK z(Z2SlJL>M!?p^4XfJFj79U*mya{;Ruk0v4y*gW`W@$F{FZwmL84UJ@|Sr1)N3Va{R zg$}k-GwvgZ29JbG3FmyR#E-^{%`@$LvYRriBlmOlI6fsxK1Z6Z4lZ;|kt0(?)+9AE zrJVp&fpkIoyv=*Dtv@vzXw|3(_cD2Rqec`z=F83uz5wGCJ!@_$nn|O!`q9>6_#Lx! z;WGWMn%mLb!jkTWwr%eFH}@pQ&?WxH0jxscGT-2uJ&iczp3RxbC%e)A*?dQ{LW&;g zq9aF7zJnsSbAtBYS>P6Jh9F;n=*RAvG2wtl)5VmuR6$P~^1@}r3)Pt&D`H;w&5+Zu zh%eFpJ-m{iCQDSBGvdeHQnfICpLxuR@z{AC-av#cZDb<|ad8LwC|fDy-B>iYq~A_XITx{e7ts(Vtk1&uGDLa*!>dddEx3 zMn9l=_bUDhjVW+0&4&=F!xpKncEaD+xMvZJXBx-RKSjFJP5Z{l6`rnXB!3PU`xlpN z_e@Hvk>DcD-cvzNynWm1JaBU+D6t_jkv<|&@5RB5%*uuIxRwqyPzemmUJZ+#W%Rqs z-)bT~tRp`)%ayaknc{o5YePEhfTtI=XQRkleL41M+YagK_ z`1@^K-Ca;O=6^^uR((rHZqF#YZi#_ZGaFQ4^R10nWsQ$$OyGeW6O*tL`~Y;+Kg5T| zC@t1BRy9uz_L}X;8ycLj)|J;v_r#rzRw{!a(j2?>I`*j}Z9z{rzwG-l`pQb-BE)p8 zP4iM5kO|95@tKH#TAsrjJZkVD>$TzNd3uF`j5~W+F3GVL09ertZ z$=^sZ$tX<(P7c{;GeH&$G-U->IlQjgX(qoHL?XqEbnpYMdP~j?wZGz@nDCNC!HD>l z5>K(d_PZkYKXC1UCcv;(imlQ@@#9Z9#sSt?a_nw0 z(V`zzXlBb}`h5kc8|BiAkil6fQFdfaw}9trGSa;AbiWcH(Rm3`V-B$iKCuc-*!>bJ z@;I1tq0&0^qh;LtZ1K1>uR0KW{8rIH1i|g(nqsSnhG^3Y)lHc>i0l<)(Oi{hMF0%) zD))y~?fo{y`?Zy}6Nn?oj#AWVviBUCj5zT~s<| z5N)nG3=!ok6C3|5vmj=^2s)VO`+dIYb8Oe#1zO7bZnLoIaj@a;y>dQi|FwNlGykDu za{%jBbnPnYoZvGMt4A+<|8&o6)5X*Oc$B;Tz`iqrD`?T(uxL(o+M(rw^t6vDx2omQ zth1$b&{E^=W*m3h7ZC8v0*k|h%dF-r8_5NuSMYm}vmf@v?t+Ts>-*IJ*EDY>l7$4A zp7Y2x&Q07a#fP$`RQV7wMEiLGwbrIGcH{R+a=jfdltxP0P#%lQwocIQA4>t#xGOdl z7|ROc7~Ie-iBnCCgRF5a`gkg0aneW0dI*TrBk77+z0eP$daUkS%_^SyqK)>-Ig(=& zY;krTj!AE~zs`sX+fru1yPo<6wdmBs;2xv5W?w;$b;%nznI+i!8gbxR#H*!rcd_Rc z<0_EitGz=oy6f(c^w7G|w*H#`&0yt;e&J?9$lHOyFzIK8Igpnlm<7609ioggLSm%*R>k(@qg_6XndaqQyhY112v z=e&HJbhL6>(rZJ}tdPkYxy$$=zfT}CD3Y&bXy|*_4P)-aU`R8>lP%*)H1kCJ>fkRo zL+vmcwc0ms9Tq9|W&Hk$RD&DcKGs)8xI{uhPw$xP``ir5fxQgIrkwCU*8FPaA-SSN z4{9scJ98>dBKwzo7z<{qAHjX2<1S$=Pj->XrH^T>h%D}i3>JzoCas~ooTNCMAU6S# zpN@>O&#ol7HBp!`lN&KhcR-t#=yE2C2&PC1{t_9BG+Ha0K0!PkdD+I**AI~=g)f?q z5LbhvgLy?GYn*5d8zcsl!t!)rSyku^Pm}Fhi47a4yX%c~@Xt_pftQ6#WaL)FTnPF? z2)T)ORN=u2FEiLu5qC{nNrJG+Bd|rP3ux>9$3>`438+R17}tT7A!scG+D0qE&Nmje>le5}mxq<=g%AhVA0mc6*Ju}Rcd6G|Cg1*l#5 z6A;;L9Q{vNbt&(eQoYl`mjKh@dQB&dCsy4=Z}c7x;-UTV&qxCajqP7+v)n?@P=D56 z*r*@)hOj>rM=gzhMxd{D{x)`in(rXp$`FguL1Y^NBtdJe@Vd5We zVm(~g>^-rWVsffD7}#ECiR*&k?|fHxqT2&-YdRt9@_u%DvI@X>*}J9a5+VLS+Z6(q z%Vg#AaL7Oh9@0cgXJSU{S+YJvB zGo;apk!ITA?Oqn$;o+gap?vsX>-bwhH`)Va2Wlka&hoT(ffW1{u7!RRyX|v++qm^z z8@r=Uh8;g)$1(h`b$R@$pC&k;Cps<=&-eINcPvC9h5aswR!ujx(;gZafN}drJWmw{ z@3JCvX+`!I)uwYg$d|NGQDj#>r12^zTKD%-4wtA;U7uTuYmX|Y6iC&4Ayc*MhB zwMn4H2(N6|1Mp+Qy_c|Owe=x2yKl8YQN)mG`%5=210XCRId9u#t`k$gmBEkt&V>Q~ zl?q_&7natNG>8P21RXp0hbKLYfB7@MBpNJA4iW3k=ZQGKbU!Vx5RvbiZI^E}b=*E@ zPa(aPS@n-AJl_l8hTpDm`5(xyU`uw0_O&IrD(z}Giw;&d`*FtNhdo|D>0wAbs4lvJ zq0A%!D1x3bh87_=8{WqcGTh!H5}q$1dabW#UvQ5-QEJqH52a29mH_McC$h2bryqnq zJ3L3)4N*LwO1gRQx2BFQ#yEm29bYbX#~p|5YG~o4l!23#2*X`7u^$G6QStfMW&ZR#A5bVdGY2!!fE-zf2$+ADh zKzVyQ-Ru>(bUK0G*swrcqHUj-UHRaAb7AUx>`@NC^uL5{9SOkl*XG2|;pca_JWMYM{8aB11D8vA;_Dnhwy~Ylpo|q9OK0uIbJmJa!XP z7aITAkKjIEtGNE1A#Y#a$=i}@`^m2lW&d)5y!~RRpLZvdN5~}Vz_LhAzrzUF`^^rg zMVa>OqXgRZO8->))=R zTChvAd5R_Aj%ax_VZ1D0c%)R}L-ZPTM2~96G9q)%<1rCX4oZ_6EdCvj$6!wHGZxZ% zJ0Eb&FtTYds{Z+&0B*7|%#C(EJxcV6kfncOr-e})c|kuKbuFy#{3wF?W54^S%{6Wcz?MNeQB8*Y4rq@=9fIdSL zbnV~?4t#WI?Hs;X0$p770Y5Lc*|gbMMLtocFaS@?7As4&8@KQaWM5)|uz3efY$2EK zinnb7nS)GucL~lu8v7v{YbjbYjjVq32W4S3EfQWsJ`YmOXz}2pxk#dZl49K^k>muH zPNMea-D~zL$PZY1j-tyJmU4_*Be<9bM&?k0yQC} z_3CBlb}Horaq-o`^qgpiWoEvjU9E+uS)w96s)p*Wk7Z3Ce(OEZ3l1yjaCAFk)y?&m zwJXn=?#4#?CYsN6t$c-?yX@h0sFu-oXC{B7A7OKAg{A@@^!5fhHpuTH&)`V*DmDaiSH|*3uam;IS6{+~co3 zRy_<|klM=9h@U)|M!#avTiHLG0SLfkr+C~w84N*SU_*lovv^UMsvO)q@@wVyPguGm zr9RMjQ^?fxg+Ns6=@V5#KrT`mC<9PTE05p)fiaPmcrN`=I7$X3+`)KZB3}yrx9hnD zHl}?tWjtCb*Rjf7~BANw8&Z{yX_o^Ft2uEi2*mi~f$l+ z>3XapPDlP8&&@XBzeUcN$ASsI2r;BiEy^pfvtf!Ck!!=Vs6J$O%*mAZp7jZK_0Us= zMBs|HG1)}21Mb2yW?}T&)Tc2F#4zqufO4{z<5r%2?nt=AG=9=Fc)e#40io+teR5wg ze&S_{Z)fN;H{K*lz;ht<9JRz&+q3dhF5|JEz2a)eMd|OQSp?O@?svBnb+^m&%*O<% zzJFH}S=Qj_QkA+`AOn0G>jsR~;nC2=Kw=_MC@JoqJ2u}L} zK7qrnk;~kuiI>MZlT#DVQZt6JZ#X7lDQdmZ)PM64UsKXa67I= zZZ=y6EOti%vJzko{IIef`~&%vY=xIStQ`+wdkI?c=)?U0VkEvb92SLdN{_kWBt+@J zRZm!w3vVJWtcC4I*unT55E=Wamal^+IwwU z^E!d*B#O*fz|}r$J*I3vPB{y*Pa~`SR>0a?ytoOvz?@z*j#&IR^5ClR7(Mf;JjHbO zGkp}-G$eD#(N3c@_Aq}>q-M@EPHE}yw#G2_IaAUZQB*<6{K-OZ7SubEpp_F|byVDN zcMrlg>a-RzGbb_=#4=L!N+lWX5CjB?uA7S(a)&+TE39I9bRHLUq6egCJNROGCQMx; zXxfI{)*F6$Px29&y!2;L>xz?_xUVaWDz3}*kxXzD%aprbCWPx3tBKB!q}Dc4GxJfQ z4McbjTq_~tiA^4)c2rOk6l>_hWU9SoFRW#_x>3pa!}++f{Vhwy5Hw*Tl1Gf0ca(G3 z>+-Y}!Iq|8ocW9NJ8G+Dvoj?2h*PiwBVpu`J`^+daCBKDJT?##I=B)(nA$eFUc*gt zLWuDUHz?j%2U!2)y=JAKF{EMPkJfI^(hnn7z+FT@GX~FGvO}f_QyT>MS9b?hg1 zflKz>!Ek)0Q*`c`s5*2vb)!e3E@g-c1z!pK_{oiZrc#9$sNUV7OBm~B>CU;|B6&@# zcM7GJPQ`kufRMVVLGCOc2j2N`+! znt|deAIu3;Q+=5C*2-F#92_e zH2L030B)}*0In7n3}nTLijZ^ci<6d)PF(x;J-5*onw#QQ8Q2@w(hLJcCI}sKqEKP? z<_^j?tgxtMpHsOJen3gratVuSHOvU1a)~{0n4zg#m(i*e@vOCV5sQMkrrU zSGQhxE<1141y1JPsafebYOw*~D0V=Snf1JB=UbdccotzlY_MOmA+<7Z6m{~KI`vQ6_06a8ymj93&IXBcgH91?Wfghc1L$svwyZpH$sfPY+ria-?oQ3 z94F7Nxp$eCu3%;I{9~)Z8MIRm9R5I-&_xe-Gob|-+`OX^;i?o8&kQ#%z1P13QN&PbY|TCiulZ3 zS3wN;_7{FiW9L6?F5e+vWg(tjyusv;3a-%85HIke&d<43T2BI5SAlbo@k=N+_q34` z>1b6_l_KU>mC*AqSa;+n94TB_ketfKP?VTis45jHEuP}K2wQ+NDndcZY~pDf$vInz z!97(GHu5U6!4-08Epq9Z4p7Pw6&>YI_Q)1f*;Q+aok_aE-#d|6Zw`v4TZi^k}b)m}EeVLMK0O;37ys`BgBo&4}ZcsNx`GhZj?-owV7CtJZivN8ftMGxG>u^b) zRjEN7WYLy0!xE@bAgWU!E}Jo~vZ_%aLnrRoDf4QK_X;?d>E#5jM;0CiV*FrXHkKt{ z{w2}e6j@0Z5vzUjQ;jXRaGbgQD^D>l>0q*oPQ4f#s8b3LVvy17-HXbK>}ktS3X}_PRZdW}etSo&RuG6h z1rI=LYpg$18b*?~Smwi;yJLeG2MIw!*v3ZU)1wIc4rv_qDUG#n=pZ>%ZAwTSW6MI&F?lY_;r!jZ1l_FJd5THCH01pbR` zg6sG21}F9VC|qDZIWu3O7FT0F2=ooa97R|41FpcBIHXuC5#UNrj@=v(r89 z4;QxZ`S1B}vB_8G?O$+z@)1IQJ9QM5Ad0WC?G0R+F2nUAw;qlan=E6^!!KxQnfor? z7G76YNf1UhkBq?ZQ1e&qF#NHGASy_Vo~5`De}DewvAS8mZ`ArZNLxj%W`-VSzM$Kg z@?`AP>E_A_m!}e&WU04yk6arvgYae2m zv*Z+x-%fdar3yyVi|@B+F1Yogp(TUc<_lwyfaE;@46?*sh1QA>d|NQ$y=`hCJVmp= z&T(r(L#yiy_n4r`R=L_o+uP;7u3n{CGtyoe`JcU=RU%NZPB848Ew0(=+_IxQ#4-9b zwl)%kA3n{Lw##>Fi8jJX8>$E;fw?ju$QI|_XvYBbx9s2<_Kq*h>W#LWkxZLbvH9Lf zuDoLrrYyHAPAl14a>|ysZw1>0_MG**u1t1cH}tdS`*~MqDAoem7(kq~E5v`UT}B@= zBwsBdf$4U)Q?483d7L>;!+2xZX%vp8K69hsBG|m+FzGJeKSV1U-uSApU+7*H1PBpD zMOH?h_urg|Y)C;o3;SAm-d23G%f!Ht-9oax#{jLL7-x^jF4e%uaBpzoQL^V+cRc8P>FFVdCFhgKx27JC`Fthnumf0F>1zf*Oyr5$!Py;^@L?!=&ZX4nN8n-N zw>B8BLg>h5*g@U85Oex$~) zd~e@P`E0WZ(&ypa+%gt@;#DsF17rXmd=D39SLnx=@l-7F%maqwBv*TgeAkC9pP?-+ z-3d5aS6vmXjkXBCbUc5rDOPe|7nqAfcYDS91}4xBB#d{*Ld$Iqo~phG|AE;QtRi4` zgm@f-xLExY-?vIWI~IsZAZQHJ;v&Sn+kxz0dnE4YDbRh}C12 z=E@id*u;x@GS}vN-IQ{D;&S?6^Gah7T|7t43$Hg((`vaTI$M9EyvTY|BXl|I*xuLqnI9=Mhihg;w6oF->>|fCEp@OphQ? zQ)s8(=I`my0;oy88SX^2M2C9wpNQriLb;0MEdj5S z=d@bUv`e?Nk;oDh5x(3px|A`l+@+md$J5}gumDsd52YU)_J;eQfJCURSLiu(rkIz9 zNAx7oN#?PLoW{*cYN)M5XcgN*vpW^5PeiNl?hTxZEZv= zTtysFdsuS8th)lRUKU*20|+k#h&&qO#$%_F+!2t=K>1ohbv3eABt|VY+zw{>R+D@5~YPz=!YO$w(iW$#GpVt5C|oV85zv zdMjj{s)O~1M@DKpj*D@Hqx<9Rw<{P(H~G<;Vep*FNb!^Q`l7F)6%@7n$}0F;E1UJp zOBi}BBiBcGUvK4_mg&SB38%Ry6fp+0v-1@)y0U-IeR{F(52hhy4@z=$f{`i+gPW@d z9Ru#DFu}zALSjN%DDHUZ(9!J`vX#S~p!(+r?w=?<7sQ0!l@YNF15X6@-3k_?WBS(O zU75FU*QEYf9jI!&i+{TfsCEsw4hVI#eK94ofK zV-f)24FIta#}A+g&-+{4Y|SCL7$8KFot@n5U z*V1gQVo2vkyPJ+g43G%^HwFvQcD2z*|P3y45!KwF4PGV%?Eu0nY#A3d*7;isn z+Wdx>{GxCiTI}%(LA+>|_ad1gSU}m=))eFJ$3hvx8yNA={nA>5$ zrNc+62VeR+d@b;T@i&%f7EJt_OIGt0-bmq_}osNOg~*aY-3Kf5->!t-Rcz%8klbH zm+JJq{{hnK_{p$V4-Z4#;72SY9?~cp3v=WxwEZv265MaJA$gjWh$c+*nt{zrg14EH zUA~7oCc*^T32v6CtE9aqym?-KNV{O~xt);U7A%Esmvh5yeQ8FD6jm@2IBQYo23!{o z@u?jb^60C7tcY8VI1?hC?0Orv+sC|c=Wf1#^w8-w9^V|Z|LfVjetMS!?OX#dfH5E; ze@}3c192C0nx;ekW1b!Zu;Jm3$Lr-yK>zOLlxSWfZ*-B*?{Z_3yH@F>+^=f&YML5G z15NKW%36Qm(uYZS*=ce2qh+J-V6}Qk<+}v`<3(QUCWej^#OgJr^KN&9!Att?FyP(E z8p!ucmY{h%?E3vm>@uSFK??Afb|8bPoJO1EywoF&cF7f@W{f>)LIl4qpk)VKfmEJR zPF42A(`@TDf5e_}%)`Vrn>AZ)$2!xxC%+4M|=_Z6>{W|hV8Uy0}4`}@+nD2D%A z*lkk4vkcxK*VV;GgwrlpcYHF*zT^4OLdoHl0jxpIuxC~@?iSUnn-5%$ zuVoI~rOS|sbiYo&+aBQs1)N%_t$J_Xq!!ugqJZqb3i`gTnsZCbKICOt@)LEci7lEeNGw+1qdXDNV2W>6#c1^i4YKptdj%)?Olu z9Ih~qnIBvVJ*79jdv*LDS9EC7@Lw1d(YXtewY|{G;i0QF7SxvFB3dZI5v{6`pG2~3 zYt_~dWwfQooIU8?!%nL5%i9f6^~P`>8gY~WtfMHbQ#q!woV)=p9Z7dSN%zo6@Znq5HWIwp zlHbsSibi7_X{gVEy^)QWlBFe@`U}MBhZFm{?g09*I;rn;7V;tzx%9YNhGH84%~g$tg_ITd-?o#zLR`UH!Q8(# z?DvAl(JbQ!dbnd7*+UvD8uiix84u~b7O?v1#O=P6B%`rye&ghVNnIo~()q0nN>d5? zel!mh#+Q-O@2hDog_Ke1X#An9oIuKS5?RJr&Z>k9-wa5syN3Ot9Fw7QFiCOlLSLnK z7fqW;(;rBBmrwC82GEP=KUnfvXSm1AQX}!QnWAjL;J)Im+~`hffzz>OOyh=M$gKN| zyXC|hzF6Ej@|90qlZL#S7^;MX%!7}7LlJ!6l6{)sIFQIujo*lOrz;ZH7gsX6y6@$ar z@rs6PjbYK15SKu|>0HwY?sK9*tdTk(cPDs@r>gBp>)Y$VbFZ7Up6oM^9$2^S-8>Vk zoezU+$;>(*8+Xw73)f!OZk)5yxSxtPP&@)gznnc$pn6 zj7}ux7R3Gg&p$GBbz@}0nlf^ALg<~9jAak-bW=QGFgj0J*gs))f9ob(PyfhB(v6{S zP};e9xNl{-#hr3lk8c~#>unk*9vHe_Em_|*_J8eiEOkgD(Wbb*oSx69-@}^F`e0*{ z=MTP)ieM>vcbcHBOmWvV?tE^^$kB;7URT~ zm>5bB!Jt(1*S*7hQ;N^aWm6RCQj$D;FODVTgaF?Yjl}oSV#~|>Tf?nmtLUY~yoA(I z`SDZ5U<$35l;<=SM-mp2ZXkU^qqp=})%AY^$y_-4*WzZU^*u&4$4)$T*nr85y$WS&AY>e z@Sy;)fU~Qdf5HDEmBm7M1#P%X!@ThCSn~{{?#qg}I(PNN*j9Qystg9$HZmob3i}Ag z>+F#I%JP)M%rZgV^0TCBi$(tgn}^tZ%{MI}Z_5&F0^8xzGbAAfUH<^6t+YySGr?^W zL=19)QU!VwCPXWWUA#(eHZjUkHu3vb80V$yb7KF*NQW)JkD03?BfLKXcWT@> z2yWg#VH8ipc<Yo_mZ9L?q0O7pcM(^b^2;G_&`|dF+*q^o3Od z^m=~44)OliM}Bv|J3deBjmUK3jY`jr7oiR4!*a8yz9T07HV4Gq4ioBb-!*yPNWG=k zKKHXtsmn^cr`lU|!rOOz-{(^yF<|xk(imf!CsE7i+bXR`S4__8XP}3DR>;XNXi$Ov zLiOq*MCc8^&5Zu4;3&Um>!OQNkcwb5iuUy(jUQeJb#~pxa%Q*kMGz z6PGyB0VyMNYSF{wFH-5`M)cJp0on=FmZP$gRhi2&R?(UG1lu%NdA*CBe8YCo!4(Ucg zy1QFChi>WadguQ5K0o35a_w{PwbrqOiB90KTj*%yP8?_x&Kl^xR(FBhlcI>?ub4Jd z{qd4why}@4HM8%mx&#|BnRK&D^S8i6NRyW5hHaj897(sqDnQ;M9LFDdSwXyQw)oMZ z!FDX_I7ZdwP}9)|e~3qui-#fCj7f;p4>G&7a@_}vl&@##AlV^FX?1vsbxmyF zEhceL>3|W`jNtrOVq7cmUQry-w$YQ$nuGNz0n1i)gg!*G4>O%DUW*?VMGjFld<0I= za%?AKM6L!=_W6$DxO&iT9i;3tL_DRkZt~6aoO1RRb|#gwK}u^=jVPxM;yW(MJKtkS zADHyzXlQyK(4={m;1HO#(A)8R-}_Q}w;MO3Y}|dv!84kr@bsj!FhTBZAeSy% zv^a{_`cmDV+xLfaK{G?p>c=kzSiWN+e4KQ?+%8Y$yf7#40q`+-wOvz{9G(h{| z^rK{;$SRw&iz!L*9#wzg7GD#)r_dB7L8e}5k#*O^r_B7|2?X=Yk zv|@|-&GLS|t2;w6%twh7WWZx|-2Av_?V_{?%*6A1 zhX*|X-qUj)`2c5rOlGdwlem^=5BL+TJ5#S*ufWw$Vr)V z&@Tk3*8_rk3-`4*>XPi>?n}DIrV-L>wn|yczlzbYJ0_2|2Qi;Fvl_W^0~;?=X$2kSbKuK0&Q6eCPDRO{&zqA>e=Fdv#U?)R=J?ouIl zx`=6apYL1brF zVeSPV(=A(5`B)o#VS-uDM{(;k!u|K5)c1M*GW1Y|NtxWDJZx#q1(Ze$+*gh8+ZvF_ zJPpqDd5rT9Ti8Zqso&xD@j`7`KkO*UvnB_&sKvhjvD+kw8Vwk*!OpQofg^A*myl2+ z$CeN}W_waKSmbn=H-&f|(yUDT&Dv!-M{`47KqM3&Q>$VrU1rsne|9ar&l~A-2B79Caa}g3;afS+NVKjaY#I6 zzl}RfMhuk<=Ft%`Zu`tMdXc_8z_V>Fi#`~?t@6ae-up0n)g|`SZ+*B4CE>NN`l8Do z00VUYa{HVEb`>xNzee_w?E(KWmo|8m!NY3Q*Z7|wCOA`${N}UQzLa^`s!L#AfMpqs z&$a}Z5u1>_&(aC1CM57={Vy?jUcbR?d^E&vkJ?SUvN8=>UA5TT16LifTyH8QvBJe9 zjd;W-%Rw&&x~89&I&CjF=ZWlq?}KB#x=#uVAGU|zSw|<873Hb!nadgG)$HQgVz|%+pshEyM?I=? zsPGucZ~WHb?Y(@RL{$gLu89;%8Nf^a<5g0(@M9WPuImcM^VXJ9+G_}}s*f|1XT0+X z7(O+NHo$!}R&EKEX!}7(W!a2?JE^GZXu`{EuYcQlRy{2D_{j3!b7{f(c-VS-KE|nx zWi8qo*mh_*>w6*WyMHuje&K<~y*Ie9HJ{qJ@xlR#s91Kn`PJF85RTPV3cZRq9vq_D(aWH> zb}?mqx7X<|vm~1-MrG(c;RZ;>x#2kh@u(*qIHIVq%?oW0$)-}G(3GqZ0dMbOr73t8 z6gu11j+u38<^J@CS(JlW_=FiO5s~&~)9Fh@@On()V2pvQPvNRG!BV3{l6DaBZxo&U zV#5x-9BLD&ox;W#Uciq_ys+*#PYjYonNkE`_1(I9>w9@COXqMc1FVx%HKhF?A4o~y zxpV;}P8dd0;=Ug}>z+PGM6FU>!`FU@a~+%$@lmptu^*y7`b&3qq+xw#DM1m@ybSar zh;t{J)ATB+@WQYuR4k^6k1at#^*CC@HGGX> z6;ET?U0?EmEsL%MT4fnuyH^xLn}8TJy-)}f2sd3@x!bQkjnJt><2;fg`;!W3c?qSb zPR`!1G|It=1-F)_Iy(&y_IM#Ztcdi9lgRad2p00l&WTp~G{Alm*+YfV1w!0FBLN`F zPWvPJfGu6is)h33>kmcHk^kuB?m73t^p>a@Xm_c{6gu7zT=xuhP_g{D`lD*MVS2U2 zu;_ty_58aS4(ym&acdtQ{XMUZl`o$O=P-CZ^}DVl0>(7Z<)P51F~aCrs26{1`?tN& zSl;f)=p?)7bL>0bKW24^7SUrTykRG3&(l}D4BLv3>1aM$JHd#w?*<)ohtC6<`hBcN zX+Z{tnxPitE7@&70LNZPg?_Dz_8;Pap&36n4JV`Rn7;6A_6Qm-OoxmvC!DX)uD{Wm zvHxrNEdPRO**>(M@S&70T9Gr%q9y`JH_?-pV;s~Ro53yi`mRE41ww`fF;|-qRb>$m zG6A3Vtn40fcY=_{F;~M!TXTBqZaogkyOh$CiK*IA_;|6+JU7h@t1UP!gigEf z$5;s%ygztiRt#5YOUp45W%qm^7HDFw*BM5t9^`Jn$FDf_N5%tT`+f~w>r7bWNK0r# zsQrO$4oeD;DMjGdG8#yWO{xysxwy#^~) zE{Ij{5y!lcw97bQGNa59*qMoonh-VlHVsTUc*KWC1%Km#+~~#PC?U`XV;5hHd-c#` zCZtuI&8k%8nNg17`fJqbl3guPj(#;Q?8d)2vOb)gRBjvuw~#N>m*%aq7j%;^=T?0j zZ@d);wT8ZjW<;HZNf~S!E!LBl06Uu#bv{O3V({7$#mb z7f9ZIcc?OgDnHrM9RYs>8>+=m=%c64f3z$rG<1ud%xtT`PK?hkoDXUlfH}QvyPr3< zL>^O&&_NG1F>gllr-7kr(zGc`8Gcy(De9A&5xGhVokjs=@lBW&e(~qVj?a*=f?0LN zA+a0o7_WJ21F)lTLtWG@?2CP@zmYRROZTIE$kiK49OeXFebXmgrd~jj3+RIow_GW* z=Qfx2PpJ*5H!#rnX#GfweYj;>#r)co!f&w|z*QI~Mfv#Hx7YN+i|a=PtT(XPu%FBJvbmxmPXDgPB9#E>0e)wd#owWg6x7f^QG4zmIsm~L6IIg!~l z&Mn{6?3Wr-4FO_>6*A#ur(Lsj$RH@_4Afbwv409|ZM!9}vgI;PY()6xNeTVgj6^2a zDdU|XsA)8eu6}s_=6M1wc#nyP?a=UI_@C1xP|ECTZJKZfB0P!cNM7ytP5E9O2yzJTPQ5`#y!?F9J2>A{ZjKir7fSra73hk7^0}AnTQcq?9E|%QV z(1&mSmGiOFojyX6;`c%LYhfW|UcYE_Kq)1G|3B8HC2$__Kp7ZM;PEx1ta|9XVu6Xn zM@)XvI9M=C#B=3Vxm4$}k1q*@r2QCB07mJL5XA-Po3s98DG0(n<}sB|$Oh|h)euV6 zB&0Z?(k@&0wi%@wcpaRi+I!Hh*(;PU1=}Q&utXK6x0|E1A8w&}PKLz|M^zPClZa^B zTP5jC2t;jU&4ix5|KzY+L}au=qG5eIr4!r-G0R>J3$Dks9i^= z6{WiI;ySVQ=%BRywW247qtBv=Cf16Y(x&77>U~g7{#rSCb5nHUtxYgjTKT*8-zJDV zA6$q_S#`#vBt>z;S_OmQRtzLrj{*f<#O&u&KP`t}brg!Ga-A^|qq7YuL=1G{xu_dv zMGki1+6KVcIssYKzuAhFEB3@APT*U}EoDY)PGxKLFxOxIqr=bw%b5g&QTq&CiL%7q zAm_0->fLR!?;(`n!)Uow&0zN+e%|g(G-GLOX~%~mrrhA5S%yb#kv+w&kmbghAXMtyxVq;&dYQ zB%uoz!Y*0dxF9uerJ`}fOu11?bHI`_yHLrXMBwy#=a@>R){0`JWz zo+wj_h_AvZ@YbLfK$OLeW?OfU79nTxvg@W-V}aT-P4SPv#rZUCRKw+YsmdTAO5UGL zl@eVXPKv$e!`}|9F$Wb;e0gnijOT2oH)n;dNh%^LEAw#j0SY&h8_}M{S@+5X%w#k=L)}Qd{oNHi`ns3t2&+uvpo*7QSSySmDq9by%`Dxp~4${-ptz|CuIf#Q$-$ z!x=kmLaaF215~e2-qyF%OY)#h(ko0euWYdF*!Q#c#@kP6AMW1+q|=JbvTiwPBeuol z5u`Aeulc$|kxANTBvDTQlW89UZ*7fz@DJx;aeoYbx8bQC1fm$?T~im};M+3Go%f2bp~e90@5fs9 zGu>iYOGa^cHJdyakr(hr`C@W^tT`YWB1#!1B6`dY`~Ty|{JE%5Ap(`jD2+0W@WPze z%QlS^M{6GWqz%#)+EwYaw!9}DVVW);loKlZ^ebE=-WER= zZ`9^Y{6%f`*|EzVv-3J_QY{uZv&bk-{xnZ+llc!Eh7Z z;MoaJz3_>;m4@PPsN^?_+x=;#W*j89;w8?=&H9Y|y~GlV72J1uaO; zMg|`~^Rv`g-@$#~Yf!$Fv|@?4Hb*U)Di2vc?^uysY*pZqz`60QBSTYJeLNF3A8OW9 zX>60ocfIo`H>H`*ku?p|X&X`S^q4rS{*I&cnsdSp=-X>IDEuSqXJz)Q6=J|6#k64E z(?*fNIMI6h7I}}h*g+tM{VW}W{=jnERy<%3#743#(YltX2@RC^=EW@BqQL6(x%ZZ7 zSsirEq}qr+B!KLkd;`}L^0u8{S+tsIDiC6Z_k8CeOFSbkGgP!>QzbVu>T*Sx8e zoqPd0Feh&d>I*3FHn#4jYrAZSG&}V&`e=^YKRNm=7wn}VH994tq4fX0!#0IQgyZY$ zy*d}G!U<;0KaU}KblAYg@S1X((m8+O~@2N@b^I1`D&ERFI0UT%RLOW+6 zpFb6PzeU(*U;wmpOl&2xb;Gx{lgXBMvMa5_Y-B+UU;JtKPZ}JL-b{#nX`bPgC!e*T zumP-&)PteQmRGC{;_ia`!`k|z)p9;ge~GVM)^zs9a^PziT4g+0>b}~|_xx~tQ^1y~ zkULk@5PuoqQ1Pp*F9MIu*(9$ES9@mD-ido$uH5sd>dm7sK^pA=+L7SAm`wuZ9RvybGj?2%Q8q!#QMqJcw`sH z<8@bD1{qgrbY+GbdeRcb9K6K5qSfsJmt*rj*M!^aM#inrm1S>}ONn z^Z?hc6*#V^%&xD9uHEdedGNeJGA!@H%OP6STn)Hm$z27|X|`QF#Mb$U@|fI3aydqP zIl(Pi#$$yqkA+>Pxy(mJDoTrMk#RBB+ZWMooJiAKrwrk1Vms}!_NVWsIZi0xBUaQ_ zINj1cn{ck2m+MiQ1Bo7TQHJBl@*>b3Qwf3s5#l3=rb@BHb{^Usy;mjgEi!vKvpLeV zfbO6M&h#kC1B1q|Y@DDmH^OC0!_-9(^G{56$PF{u^tj^=#i*G#7{|S?x5|QGa=SSa zDI+?WAzxfw%;3akpU|CXVkgn1zGQCkaz&!|)sBAGt)ICEv0~-7YUSU|sD$@F;}a|; z541-nh$belhJIcQ8zQsY5<7@A$u~A~AO@(w=cVA&{*B(T@2VX_-VfGUv`%-vIGAz1 zohaFcd7WhyT9GIY$TXw%=9&|lo344{@lkV`P6x7ny>sNv6#nDM{Cq0Nk6bBR`=Tt@ z9&;(w#coGkIevCEyq_}l2Q#(2+f)eplg?Rby(b%9oCEI0C-NtGgu&%`J>fRVI&)`UDCovA$&-Hc=Yi1Z`=%bWQJPar2AG2+rd42X^Stkj6^wI_{isqugEd| z>t^6VP!qGKkky@d*ij2*A3-<#@9}3ZjFi^}Y_2Snn*eLRPh^M z+MQC>JlUxq>Bf_S{L!Ro+?oBpipgUFt|VX9q?)X-3wx+1cUl?)Q?r`-Uo0k(DfRB#wHz?n34=3epfYGkGI(KGm21sY~^%5MDc zmdv5{;E#jBDkQX!k!wtSso*dBV#m>E}1Ygd(1fN;AHJ^Q!`+nE*!J7$jXcy1?+Sj^7 z9LTn7HxiNWN(JYHbxKhQ&B?CbCzN)|B}NC36fBMasL%_yJti6jPF7PumF`Ex(T?2M zOA|fnUe~}r`-V8;mueZz_TdiGt#ROAIWJp3O*3X?TlK>&MNGa_hV9{3sEjj>0$*!l zjTP*}HB#Ir9#sqci-n@ueKc#1ArNsi1eEJu=p2N(^mar=oqUZO;{5U3-i_qUDOIz( zgkOmyX58zqqd1Z41TpG2%SnBt1FXr6V-D}5j@TL}j2`XAsp?zwEG!2P4&Vk&&?5S7{Z0 z<}23A$2Aa}o=0WQgk+BX3O3nUA(X@5%ZEcZr_5M9k^Av}qWkJqMp2|FTdZ`vX8XZS zA6c6_JpQ%_rwYuI-=+iCIz=~Vdj9@_M}q^TuN@VSS)ifMDV4zXdyeR03MM_lgj74_ z{F$kk^7@EOCP-SM^}Ldly(ax1#N_x-g{CD`zXGuzh$kAZs5x=bn{ZHvR=Ggid~p{8 z@mIx3MqkTn<&W`}iS>n?VwuzAhV|UOve`p5f4q)R;{p|cJSJiZ-B<*RG&@S8z7{xj zJKB|=`BVP-nw_uLJ zJfs&Jc~y}NZYN*bqJXAQ*5yEf)Xa-e(>C0|2=!8Cp5bt;rOHkuzk{<6Aq%Eq$qYoq zGQT#_tmwn$QQ#{Nwa8UBjUj-U>%jmFNV|Agtc3CJR-G(GrUJy zeQTqM34?;JWzPEkML$@}}2gR$n zD^GbIZivDtWO{0jxW`S=P9Z=4D~1}e5H13$_-``qy5Cp|+8Dio)%B%hx>1*KQUm8d z6SY{~w#X1OW^;y(4eRkI4(BHYd(n+6!f!mc2VD-U970 zWnp<0u2rHS=dP}9VndqUox#^pb&1$@sRwT3g4Dk)0#ve%0Xl#qaFiNMD_{=A_%9cx zde)wNJCmC|ZY?@$_wR$5PYNA5odyhEp+`eL{a#I0?9hUAljKa*+URhyD>hCQK^PM# zfMEfnZum1fZ;6c_iiY~l{uNta3cGEZaj2G3Wx}9YG!ua*11Ddsdj#WmT&+{d&;%38 z5T$_D0fhjSw2CVhRk}19aau*1q&zGcrVbdpBPK9BFg7qM@c4R0UH8Tof-KKxJ+8HD zOLdY*nZj^B{XW9;`FUST_hcF?#ZqkcBSl>*rRjg&aKB|=5M2zT5Y3P2W*$_92Pfc0 zYb(i34r%Q{t;cvLxlCjZuyivhz`Mi<)_`SAxt=}MZ)zdF#aJo3S-UosVa4`2mfj27N?EWdIWfwNUiR4-NaQx_b_(m}MQvI{ z&=91$ug4uTVISUbK7OmO>m;`SbGN0WeO7)Is)n}i@m88+_d})~G>{xfvmd)`|8ys2 z>`?1>dN3C*HTGmJepMHqb=y^-Ykc;n@$JB4!-xPe#CcDBx~<0ItZb2;^D=lfLy>={D|IhuK{}VRJ7Q9gYcaCo9j&p|jFCNIs?3Htb0(fbC2RO>nc7ErEWapT7w z=XkTZ-Ag2=Otj#OS{G3K?Sqy^r$qM$ zo(Y?bFoCe~#lMOVU{eF);7X2P4T`a(JfsdWf6fia6`NM|QfT?Bl~(1M`wBT~4IBzS z*7+z)3w&u)6#ORF#+v(XA{KOxmijomSCH5M+w8LF@hYha!(`1u$_( z3$>tL{3ky~s%c8&7(>^ci)(H-LV#nGzq~Cyu>WDUijL5k`qV?Y(}*F>I+ZsTr|D11 zvd3Kdw+iCRSMr{Q2&md&W7GL)qWa)a7_hXWT*mK@? zuj~mQup(`+s!g$IyeQ3dTd)79K#yev<7DSk-_KKNQyOBt#$6G_-QdT&?%`+dkoeo0 zV6jw=P35^gH2u}-7FUNsUz-dbw=ro+&gls7d1MaR+vT`TM1>&6L2BS~k5axv+FMJ2 zSn4m11|Fx>9RhhM(9L}mZ1^M8F0yVeHpv7^C@}(x-+zbeikwO7Ipw4Pb*3hBrzXLo zBf+Ghean@e@m znn}Gsy+l25)NZ3e%t?CTk~X*-XN-|5I4s&gJhVavE$e_7oS=kssgN}pI69t2>p|Fc z;F#ihd=3ry%I4C?0y?EFPi|>bX~7c4OB5giy|MFzLU)|x+$g*E=zA{jXctL?2g$!L z#rMmkFO$IwZ9~r;nnYdEE6~I}rF$(lEOPn{WHhTxUy?py>Yc7;S7wDpbGu8@Cvkh>)IA2IL~J2a9pn z+gAIypl$oRU?MMMMx#AEbq%%Cv8i`OwB*^8mdW`&;LKu+Qpz4GfNUr%>BHuuyKs<@ z!a?UWBm$*W1M>o=_>HgF#Gx}`7z4j9?`#kQobhrMU)Ff59A{02A1 zhT^7%+~YjUInp`qJknI{Xs>pB=3GryCS~e&TCn5l0o~+2_;;Da1nlUiP%7)h4(t@{j&`K=SB-D!(88@_=oQ57&T?@!u40FtRX}*~^AmA>*M0|h!*m^y!qD=+J6-I`Y zGcXu#i47(`)PTy`U<~4`c50 zpeNsA1?o}F`&E^r$?XZ3eZ881WAxGLkB6X)+3wrY#2dYo+Zys2y>PEsiL+xd4^63~ z%dD=X7qh2hzMCrcWk#F5mTgix{(UHjblKW(%@%usdD*m8b)Rp6TZ&5gZDU#_Qk877 zQVRK63XV(SElHH`tO{Z^dejNFqU6H71S53m*IK>!y?5r)n*8DSWc=AQ+JNNZF@xb; zR;JE{Z_Tnf1}_WH~s0rvfg*m~dSlhhN6p-PS%%DZV@V z)@gCofw0)(fU>rDlg(?jEKOV0S@8BI`=4>Jv47DB(Vk4ChAZ`7VVhHe^(o_Sp#3_G zTyng|xNBLl#89t$i_pgLLjNq*r2aVOP|9mV<;?AQ9RD@c8;s})3TFp?_tURG6FvT4 z)W)wrl`Z1+zyleW%b7-%yedE}Nu&PM9O3WK*Ap2WG-#94oLyR;O&|Tj|LNQgE)JQXF^$Cv4 zeKN|smMoGHlAslZoxT?cts!BE_#|jp5Bbcn{Mc&N3PSNMICvis1#+KCDiWuI6)`YW{&-V%*`dftc7WyQ2jR32lNs7DVaWR6 zeK_g9JvE&}@^~=}UwP`eMbT)O-uPfoaQAq94BT(g8i18TY);Sfn!j-MiM_W@n-AnlYu;) zqz^VB&P|c>{`RmQaRo6N>K;=P_r$qUi&#itd2Jvaw(KLYfk=5R>=t7srPSA-_&mh9 z!o7l$;g}vjs{16Wi_WvDm&H3@#2e(}P3Lnjn?Er`W1+$tM_EH}nzpSxD-w{;N6y@J zGS;)503H|jrS<_}_PO zN?;CD=PyS$1|nV+;zkYQh5!%qNAh?iO}TvqpfSEQ41ks6YwU38!@K;2aI@IO9Z;ItB8I;iCt{gQG0lNZqDm zqv7Dp?SNswC}w7kxH+y6Isf^RC)PsDd_9pWq9r0oVDwtPC+gyXv%%RNgfvzM)zON+ z>y@trxgaYrhgH$MIrxG^RaK&5e6uzGh(%SgvPb^XUw=U*t@?SQsmWS^^TaS}lvn)C ziGmaICsA<0^y|}C)dT&a1`PF~3L+m;BCG74rGuL$`ZsZ_!kk|IeNdC=+dEi?TBiFc zJ;ra!?>QL12T*r=HF?bONe5!(zCWAld}6buP4>9#^}Sb|<&XZvYyMADxSup>wp{7(c0bzjWTq8Q0k34gjn8h{D$ln;wj`cd@X(clR~u+5^lOU$$Cxo zDd?4;o_Ly@uos!KB+#VOESZ?wqV%%LXY-)m`!>Dgd@QQcm(~8MatQV(Q}6iv%9mEM zNj~E)I#Xv8r$GJTU-1!7mhIR~E<}b{fm?2;Z1fuq={5N;eGtzgL>x989GDN`ym}B=&VtJSze2^2ox+*^z z1{vx-V9Vralz{-MHUBeBAgyV>e-9;e_|bQMBif-#{792XnsD6~Wt2CkD^k=3J*U~| zim3Dc`}BnG$;BXeR>@S(M&V2Z^UP*_XE>2y7Gwe_;;-A`8%*>-h1!Hr5<$Csiw|J= zWREH;)onf7MFrCV$r-iV$RJpSP|Y#kCN3QDU^sY*@yM04F3Zlu| zWg3RRuf-a5Rs~>*5ZRmb^1&<_d1kDGioN2JpZRBJ9@=Wf2Qvg+D;5RMVA2ozz0Z!ok<4f&A^xeeVFAf?$;giuOyk9iJj6pNJF^ID9uvhDsqzdYu= zMD^A=thq?^O_krkxO|~id~WC2pgfo0%{iy%X{so{8PR#S!nZ1?34=x1+`9qB zwg$HlTG?d=%QJ;<1RKjtyIQN58FLSo27q)dd#!f|A$K+tACA{L)w^5U+o)>dZ%;Fqps%f_ zD^sYwV;nzJx=!LbqKt@np0%_VQaZS)UJB@d7x(d4q45{rwdf}!cDbhPVC1E`sYvgF zBT!nZoq$GFUwq?$rgPDpjyl*veie0>Vb|*e&UNVQtwfIm)x_%69*&@VTurg|Mr#%sw@HkJzWSqU^KzTzSB;>zv_m+k-7@?bx z+%&~}wnX`^Gi_?fd&nnUgP1&7DlpbwC~jo;FT80p&qzU)7O*ta;4TO>r>RRW+V zn)rWEcMP_N1Q_L~X-O=8)($O0r*@5gsL@5|(`@6QQ9IqoqmQf}DH!jStg;BUZfQ)Z zJ7{`zkTybDA>!XuvszQILoHNc>z8D(IQ&%UtR^*o8fSN#1{w{?LRBmfxl%U)d^J^+Y?zwb4|it4276%4H#Kr862gdN~H>Aj<3)B5mtq z;GSiViq<(KT48U5!L2aRxCB}Q69A`YPA1dAp+1M?66)bKTna;IVc+~{nR zOpTR$#T{!g$pG>g#G4y~xL8pRn$;{R?`i3edg5LY(IXIBEF|iCK@+T~;2#l>ZV?gf zE_B$vbVuBCk#Su4^v94M03*&h!>pigr^<+MzoTyBN-O>%`l5VzC3qGKnv-jGH6txvqt?a)llWm%J+-X6d|jrzD<4kWhODP(PM|<{ z;i7d)AXTtuCww5~gX%*$ui9TFIUsU@WXrt5a^>T@++wL+v;o%SDM`@jGp9>he-L1k3?5*-|D9(L1yms(MJ$92 z)W;b>>VM+l@|NOcUyJGqZslRP6$@3p+ayw=lXIwrUZ-tw9wnv~}shffiX;|I> z6{CL!j$v0?!|B`kSg_~ zJ-+YfvF9P@-@StIQszwK8?In3ltEEMZPMR3?&oTXvhU;qWzyv0`uSxD$IFoYeVNi| zi0Q=5DdC7F66tJcnQ2vNhw@XQOV&AmvVSEu)L{NV773Mpetl0-7iF2Q9w$fKFPJ`f zM$%4$OG9y1m$S>yZ$Wb7CwGnev)brz+s7l+%WZ#L+ZaaT5Ji-pm2M|TIsCWk1)VZT z8*~NRal?3%Pz1 zvG+Hl-(W1XU+!^-P$L}JmDAgTESQNji5TDinHJ|&fO}uug*4oYgAso9C31a9WJPT_Bj}q z{MC6xVae5g52(UQJ*qXOoS^6%r(hKx>iCONZCP?1givLTu$FNAacq;{6;=lXpjtG# zOxk%Gmr`b6X|rZBw)m-KSp_5z26fJY(nDHlijvTd3o$bjJC2+?|Hp!1F&puDlN)Ku zHH1P*7ln7tF)8rl7dWb(tca38RT~l9j@@(q{iHjsfp28KACWvNbn7^xFz5nCAnv+u zS|j@#^$Hq1?!xetT!+7ZPo=X(R8SjoSY6ZCoD0GH5@B&RbdzqhP;-THCI1z^U`IDw z*y>`AxGyp{KSPh;RENCjkawq!LE|Ko^*|6szj;SG#DESE?d5J_&>Qh2&0@uQKc65y zkolp7<9kx1SI0g9JKN$xWU|hh{x!8qYyMCK)^4)(9WAHKyMd5blKRwc$!TfZ&ySn6 zqBu9mNvR8Ingu-eLmK4Y#?)saW*t}P%mL)se@JPiut=Rp(p(~-@XqUt#SOik3fZQ%)iAM(PHNIMeu}`WGzs0Kz?*KV=Z+!TAa&ilc_X|sP z^$t+crnFB7XSmxbQQXdO-dTvV(*}<7bxu3Y{XlzYS1e9-6s%5Y)+iU3dW&{}D9U%8 zfy0=;l5A`%R|y~=rnB5DrC@Jy2~QO%(L72u6GlQZf1nz zpQbGznu#5};{!&kT$>dMf(lmbJn|x zT^x5fW@faLbf>JFnco6eaEzktcHO-F3~;V2*?)4_k|e^5|DoXi*@9!V0y}wOSoKEf z=%RlyjNwMHw~770BeWJ|mngLPW!u^Z=_N%yj85^0sh$G0|n=a4`92t5oGm5 z(e%1tr(q!QMd{;iDWs^yd}q+rVs)5U_z?qxg67Uln^@fD-QfsIeqIgL*D&&!ypY(> z8fV@QdB*wz_*|6%h)(Twq?HnP#KzxzUIr&ma+1{%JVmprVqrAu8NdZIdoMrc1;6Qb zYnWLmUMMapv|9WO(K^%_N~R_&in#&UcBfqT*%uo<;KhG|iEy*MkD`#cP=`Zna0@VS zax^k7)~@AT+E16cR${89SRaTEF>b$LG9vf`A3_qp4R^usW(}%i)f&^k$?S<&Jq=B5d5lt+CCOw<$iVr3hwh_$yh<>EVK* zmz|%paIEi;3zja& z+K6%jp3lQzMYY#sGek5CQn-Kuuf8wFzGr{VoJ^LhKL3RF?s;}b5mD&{qv@xaJj`QX z2von_!!gm-Y`KsxHli*Yx8dE2W$TVR37-cIA;&w6bUU8y`JwH#b4)y~`^n-8Cbb=6 z9rqXiX`MaQgl7QLoUT_Z!AaCG4$EB~Sn4@5oztvKK?5<}iB{@Rsir<_QVN|eeU~~B zOX@U%t~ARB{l2^BJmKohLjxI@z`d*x58iZrAi=HWh5Uy&le??S?Sx|e`icVnk5!%xZtkjT1e*dg_``2l6+2ny!t=aTvu6`_wyiKyGDH) z;xCTlvxK3T%C1JyKEOA}?SvP=dNRZ%5Q+liQ=>;|(sbQZuRR}Y{+(OLV=GF%*cOVP zD4vgrfFpRCz88F!77jK5&lk}m(f7*J6X(qvykBA1it}n+aqy`YK}XKmSn~8$oBjrg zQyJ;YGEx=_GXBw(YJC_<2`|y3>1Z1(YVOJ<|CfPW?OqOBVzsYBj+^a>7Glm1@#POU zq=#rRmraADN$7yc2O15LN#ix3_G_B7R5|`koJblG z@GYudaquN@kHuRdci)iq$Xz73V)tAurDy;6!_fM78?BLH@fJTATU>7P2$#Y?R7N@; zrzfm@^F1-JbCDUeduK6g&1I9=aFTVnbfntD;dYiP@OP*I&g}y|N`L`j$2`6GWwW~w z8K8l_%CwlEwuFBx%+5g5{_MkD0ww;BRbEc{^eAFp!~vyr-E1jlJFCb0BOW*NC|`f4 z;6{B(w?9BcRhNgcVjTO#3%jW9D!JK*cwmmaq#Ge(CgTB!3?3`vauR*WT7o(!CvXX= zlO^!|XZW=N@wSihO{)6B$2>?!7>;-;9eP=2dKA)4yL{suJy_om9V*hI)!z^N<#NMi z_t_R0S5S|Px*hrs$Xew_1 zmp0+`<2DxryMS7wU7-rQOZKUpjc*Y}5Di5AV60!(7;YF~Y86KM{nbJ`0?e+)4CV>uYMAhn#FM-*LZE@Z zXO@32?<}u3;1w*`LjliRT+0d54P()tdIeGUgc-?EWO&d9A=`hgv&L^>EXR;rpcPQ- z!sy#EtYU29nC@vpa*8m;+F+$Y^;;{%N1F8T^~?yQB>g*%*AY_i={s~;EK zCc#>GKl(v?V^7@5ML5|`Xn{#JsyFo{4L?32{6WId#8y*22 zKCA$7TQEs4pJcP_U#78v8{|&5TLHmDo{)2R$$OdBJ%cFvqL1OMHrnknOvHmJU>{%@ z-yzR(cIoifb9?ZG&>*vZ`Zjw(*4$sr)*t_7czP>3{?$ad91ZE=T5@N7#`lMF7k~W+ zrWHB)`Ug0&@~0nNIF8Yj-a%vV#+}BiU@zUE3o#e%^Ch^)RSVP>fqAbA(Iq|gS_ zCwkMP9s4ibn932t&)H{s5X}!hU`v`CyAGzkEoQ3*R-Ru41nJ5zSho~`seY}$ z$I88U>$e$_DSH;$mIXh;!vxyD)2Y*|p_$$`5i5iGIi`)o%>1=stTobPawrXnFPch* z>okiYaY6_*%hxABd#j>3W@6%jA!jUrpqX>g;)d+xCYDWXUJA+%_G$>rR#AAukZ(3w z{YUowX0?55v;L;keHCA}yaF2kKoKhwa;5aUF)hJy$Wk8CnF7U4%d0xG z?0g-h@WK>t{3p$CC66z$VPVmN@E4_p0Jnb5i~VdvgYH~xB>@-_Sk=5D2TpOe$o}h9 zC2S=Yd@@VC*eG(ezxIDn5)HH$(?mna$~$iBCP<*~!YAza)4zcT#Rk8NY-WirYWq8+ z5;rGE>q(NQh;AnT+8d*53Isx{qhDmPau;}dFcvpS9}06pU$PEItiauHV{EIe85JT= zIqWs5y6;jm@CftD5W=Z=NVQ<3`jPTu9Ns77!whg#}7hkY}M! zN4%ns@-Pr4@W#phdZGNA#3VORAj?|h|I5yU_6H$pfgI^?a?#xo(NjWc4(uonQG;aB zUxO(I4CvuxxRGSL3dFQ~sBqz(-tNJe^W4ZdQc!(pZuvscdk~vc9rBuUlL_eEbbdLi zr`)D|ct60f5zOXwXi|nQ8sQJcelQdf6G3XAegv6#_6NE|69!&n=GmIV9dg!NickT@}43_3Sq#_kER7x5{gvV)9r5pGNnyIc2MB`Mks z+GYxJUga*v>@ANjTD(rYS{$TVs;%TS*(4OmJ^y36vTUzx%4ez#!eaIZyw_F$`RN#y7ZBF)oQPb9icB*5HPMd)+{UA ztw~$AR8VUibWRY3tPq5#@+Zs3N8)@A1rAV);+bZ$yAV$&_-y(sxU=9>Sea~=c zri<)Zp|UhJRQynTGJW&ZICtr{0ripl)Mrd+er3>1>)=H`BV)_)KTSY|!DN6q#te~q zen0ejlR=&opf*W=Y9m6K(mplMI0e8iJ_})UOorI*KyapE_HWKYSsEi)-D>T$RN-8f zr_H#_;a?8AJZZO~YOX^X>v3S}Bo53!6SVL?fK^QhgmOK5*vsvB>u7pnt2b2ljo%kY1wI~Z;w>tJ@`&Gow))*VsE+TR1)Oabhf}S@ZT@%3pM+Qf0?UCw?>zUuWZHY7p|kGpiFVU zUSp4QrkI+%<`9BgIC{Ve>-1cf3vIPf1`M!`K08&O;Rk;`ojdD&FmTl|=As_?{#Jei zH|^L3P8=W&(0RII^+PZu+=-l%g}!F^a)8G1DwmR|L?zlD;kBP% zq~hCDb`_LYF&<|V-3Ot5;RmHNL(Qh#UhK7EN|IN>%=w|4?NpzNa=!Ov+f!p6+WarC z+kb6g4u8|s^Q*RV1C5xw2<)hAfpDwD&4&8igt*}tXm`6{7nbd z#WHq?ZOFM~iFE8b)tPHhHeYvsgvXi(G*p;FUopmV3xjkXgO#ma&3l{WsCPQYmGyyfkXJls$jr#92Z$ z2h$;p-uwur_kLmb_7ynUL2=+wlo@!9F;mYV##RKE}z=OcvB=yj?hZ!$1%k>d@lBX>h|1SHA zE)j{>EDDp!aqR5X2Oa5)9U7gfZ8x;<&FQ{tn~=Nj(0tB~?PXyqB88GLSE*TE9BcOo`jYxty z-!xD!wzf7>cPWNcx?cmEe+C)cmM2H}B>w7eHnP=o5vN+%!F!53x7}fG$WU(lVF~}x z*9ys()mQ{A#p~t7{f)mzH6&(@B*sm|rgg*{MuVXs3&gMSJBvhQz}cWUMh@u_!WfDz z&#pHlTCuv=D4$r@d=d(w?+lp*Q&|)Ko&^nBZ7M3#?~lup1@4XalV*D47xclUmVgy+8*@6yOA$?IMG6|MMJ{ySQX2?oAV z+fEG46s5CTh9rLi45S6)s0~W9c9Upqb6_k-(DWvzNHJGXbQ8IQwbDL$=XP}IMS0*K z-Yt3zc``EYI&m%Q?1|U9!dsB&uNnk1Vel>^;s{}?7~#k`0~|xP>KBO^9`|W#!Q(=k zR34x9zme77G!o7fV=%WD}OT1ivt^1LRsW*%LoSDJd%`y-+4wF8VCuHcmo9S0RnZTNrh7P zHc4->k-`Z}i4cmm5r%nT>KRSe6R`+?kY9nP8rO1c8*YbZgmafSUAf;D`Vz%ac`}I{ zN`XwXAgZV!n7xBp;Q9$ArqPwOn_3sxutP~{*>B=j?ta`VfKm6K zy*u>K>n&A)Tj8wq!tu)M_T;hEV?Q(-2`c(CMnht3CsN{FB(5E})}6$zS7AL2(?!7O zYP3_|!DRnxT2Ov%Xih1tQfhWdrEiYr;3TbO6!Auy>SpasQzU5cmL9pUu?O}Ff&>4S zSHmd^38BhXj6GdqYSv~S;UaVZ9?%f<-9$I39WHaE@K|yy8ey^xGg-l@x518UJ&950 z5b#w*hxAt6W$m@*YQ9Jh9v7i4w9LPMLsk5Ss#L?_2nm&e^K0KSO5g>^0ihe;CdRfc zyP!9V(s!&oaoFe3Q)n+NWN4e=Zhd4KX*JDRpz8|(5v_o)pEMik-i0LJxxayPN&a(L z;>!ts9)8Q50)c`wo#Bq7EHfM5Rb1+=s%(xnQpk9q=@FOx(x|gHH zCg>Yd-oI|ookaEw0X8x`o)KThZJsLm8`v}rERwoLaJN%^qX*Se5fHR8NKz_=IMeyA zX&rj&r%|+x5$P(qXjxrLi3#a8$#K&=jqns5EF-!H0@v$X$ZyFf<*Em{ z2Ao@3&Vb`o{9&ze?bGL^PgcPz^TFb^#(oWrJ;{BZw)h;J9W7OItNP0Yt2SAlND#?W z1Lrt4I%qyPd&UYzdLT7fsrAbJx~HoTX^NpsWe3d%C0R-SNSS<;o!wB$J0%@d?WixL z>F&{vguTtR-rKqt>?F#1uJ2~}k={Vsz2(i@t%A|U%g`sJ(`&V~t%k%&W^wbp#Y`^) z_Cn$mZ9ZR^djPjE^Mz>vIP_d<5jc^U2tQq*4XwmXY;Q$!a$)wIb3}6 z6w%{?&rUO75((8zY^Yt>fo9Bh$aIKe*cI&`%97M&SR2>|x2p zBq6@YkG|O(qN!#on$r_z%$_Pft&fJ0^;{BS{zG}e`T2IM>M<{-D0)2jamr+X15=Sh zFyCKGwm)k;{Gbu-g35VfZ=$(qs(DIbx8E`&pR|XKW^~F_;JvxR?);UPCG>j#v;uq z8F)qZlO-_+DUqjWAL(DgG={H@?(DW z{Oaxd_Oi2_jbF)o`(FUpr`S{n!~1&{uwbym?K1PBf3l6J*sM(7w>LE-^*Z z&#{^n%)M#bZPNLQCmScAtl#E_zWKQq;&w6RYCPWU{jJ}km>4w5zrA5I&V2!xUs89Pt4CVd(I1{KABYF=TAtVHuxc_chjqDa*^#RD}y8P zineo!r%ND*A{qn81@+itiNI7w3t0NtQC4 z=8NwJ_Cl%(Mtlp25$)R%8QmAo8wfBd$HH+0J5eJ-2SIX`PX-_m*G~IY@PX&g___Fe z`4BLq)W5-#z|QL7g`)|egU7#tWyhrVd7EgZ*;#T177W0sJFeF-H&6tSCje?uYXovc3Fm}H8^D69@RI`Fzg!`r%!KAkSmHB8N@kl(Zi1sbLX)_$ zwYQ}=V_Mi@NoeNp!w>M&e!6~~kX#yIYarX3BgsR`QAfu=aShX11kxuR|hjW%+^#IMe9VMnCXqI$f%Qs* zy!6ItQN&A$V)PqfjtZTKj>SBN+M=8(!ZlooKJ_TU3o)T8gF}S=`us%ee@6v5vnZZ* z*u;0N;7cVN?)+~@w_vN+Ae(t$nltsR&7smwbhMKDmYTlH-=e2XWLn77Z!VtKCw6>5 zfPe+4(cBvZH9WI+t4K3gu}sK6hou$%rL-dWvCq&<-SHx>fS8ei<}~HJk-8wfL7SWY zMND705B8O`PI%8&?e*)_^{)gR*$?l53Bs8JAzxtzqg2-z8kqLGIcreQ!l~M(7kK%d zHh=XbCahHy=5pGq0UJ)u=&}YT_YC`1^dhti##?diNX#H6WD)coYNWU4W==6RqJ#>( znhcgz9cIxH(ZDaX&FW#kz;fm8ex$*Pl&f(=KQ0KKsSnG$T=OiEMSaW(4h;kJ+Ns8V z=YV11ZxxQ1xfi3)HK7`248EFy<`2NA>+xF2RtlVmXFK{7$fJ%kgZ4|923>D5tuJcP zx;e*on`Q))WfcO;gyuM4J-l>>$IkrPMd!E`2P-wnK=_VOC$i03O z%GyaT53-krco_qu5rzV}xqNWzlw%P}hk{`D7C9=9w2BBq%hoKeh{_&l6{1*k5v!kl68|1Yd(fR7~vt_WdlBlZ< zW=Z}7C;D9t$NMgk+4FHe!fvb{uaLiniw$1C`Y}9sW0^t@G~Twvf86_a^$A94rav_4 z#p8QFXTQJX6TbEOhtbqBU*X84z9p#sF8?-A$X%Kk;j{n`u zcADr~>>2hXJ%G`2!iM@K4ni@LGI^(bGBKR^a)8itzglo*c*`in1ccvdz2+Tp02wW8 zZP9tm;3wtWwYk_2tMet_=A#sFpV=frF6gKE?s{}5C%e{&6gj+tEE15i1I->Cq9k+W zcnTkxiM7>s6BvBH%@O%j&MPplV~sz7mbxO=B-I5Btc;NF^>{snFuM3^eIeaoUqz=j zXQcwXmJGfBXSa2DdB!Zqyi1cnSpn5q1w`SzsQHgT_|y0`*P+C71s#XUg4`l_shlB# z?58EF)mJBZOJasXW(p$d7>>S%z(bd_`I?+;>=>)-VC6{4yjirjaMAWVg-mq#zn=%MhG#Sf?Q>P| zf@X_)^bN8UR*nCu!z3AeUot?JA`37f_cLJ)7UisJsv4}E^|plJMPWRmDyytov6DY_ zF6}`_)QP(>iMusbiuJ~VBOLfGEO|Ns!&5kkUeGBMXGbS8-i4253AdlfJArI1;gUSL zIL8>1>z$+7OLjRsb_m6P-S>0+Ct$eC?M7x|c7-_AV4z z{O<+k3Hpg5VPdVIo)qujq&Dh<0|`NF2MII>Tt<8$MpByI%$+!AjM&D#2bz>((wR|i zX6zfy#i(p;Ctal{9s4I!B&ZG`R3`!avHiF(v$xQzGPMVS|71GGKH2!!6tZYt9{;b4 zFbD@dOx%A|hRG_S;{#haS;?Z4`9n{e(({4dyc`l7XU%s!NPUoEJNBk_>^kIDVUJEd-`6Z__J9MzPxv&(PnBB^weqLF(v;@@R_cI0 z%4R}vEQXz7uND!i_w@&YV<+YK0}Y=$sA^1^wk@N2*U(juR$8?KP8|dSz?}u34(5D9 zdFuPW^_8d^4rze`g6wtcrL=+=YrD{JQ6+|EO%u3#_EBi-U!#QS=}9YS#YY|UV6O9skSk@T+w=eun(0Erz*EXjAW zK<-rHK-M+qp0qGi2tz)e}^EsC=?6rcZU)*0R*biN+|aAAdeqq zngU)^6xzQ=hQ~@0Yb}k5=AOR^{Mk3*s#!K=3@&2s|X;}7h5`m2!1HVweM#i zbJGM%#V^*rTc1gfVg$w~cUQ>VV;hQ7hv`bO#7j;N;HRpB0b#)ljknBa-v&S7VEC)Rtk+5mR|2)Juj@_7TrvkRop&`<1eqp3}l8rLNcgN9${TOk2F z?AsShi^O(nI9*JP(dq^3+9N90dn`$NagY4}Y=jF@hyup;v>Z~eQXC*#2|b!i7}^~xkqR=o^K4FL_*G~9RhAD(*ZjSu{fFk0bW;B(9Bi}k znIB(a9dlC1*q5{4ww{-0Il^^QdM~BUT@-Nm?MWJM&S-F51n8WrOr_ z6X`ZaV&~|Qv99_qPV{O@<%U83$#s43$ScoxEfU41KR^X$4|Xrv@Uxe1nPkk6NJ@Xp zd08LI=H(P==fyxT`%WqwpI%v=2ZAz&OSP9OD>unyU_ovA;DV16c&Cx!y*q+Usy}>} zJhgg?+jyTi^98;@MW+z>YYi@%ejs6=ukBZ2QjcX1oJ>XfPGDnV%}#BZNHl>E+dwBS zF&)$}7v3@uj;xP57D;6jQ50)YFNH(%mk{OjKnA}XD!K|U%3FdU!k*1Jlm~y9Q&)L1 zd^itt9Y2(;t_3ZVP+%6B5+4E6U;7KS5Gg8$(Fty0_t#UYiIt;2*8Q}jT@jn96_%DA z`qPLW!3eol?EGs@$<0PnZpCPL8T*&N5EG!+0lp*%2fN=ahb2{v|8Ea9QvOXmS@b}) zhmFY36j3HEQS}A_E?aS_#Z>X}LzT?{DECno25c2Zh9izx%yt&`k@~0DJhS{CRFA~F zmHap=B7=0{v}EUP-+pAStKp54SPyGJf0LZTV)!`EuCeG zCJ_R1&%-hn9Si^$0e})(RxyV6FxC1x8ft$@@lHpDHs?cuIwAquV31OxBARi^+wfV| z$pA4EJ(Kqq6GUE;T58gVaBCy7PV~LmtD5+urGfp_cX=8qJmxOL+8-&xti&%6=FWtA z)EeUL6=t<#atxh>jHEXIHc0xco5cRTe@VHKC1X^La6e`#MGhk@N3n!74r%s5WXCQ6 zGnyiL-QnX}lF|Yu=Lv3me=(JWpY|Syb!UGuBI*lWUi`QcmEb}2;P7{GKc-U^V(w#J zGz`%8-aB3A!;lqO6eItxO3XmTu9!WQ{lZV$wXS)hbQ?E*{C7sUd##jEM{eqm`PWStJ$NRjz2Ek+aSxa|^zZoAMLywvsgL1Ou z>tAkSH+u!_)C=l8YR3z%ZnH?UW2A0@^3RV`-Ji>xSD$kNbKBeAg?P?|W15NLKNhO0 zOKWFlx*&aumO6HEFT6cO9NT5DMD@KJP9O|xnh1$ercY>>QICYRr0O8n;5a);~O-iZlj_u8pa`f`GX zO?eJ^`-0iobsshC^AUdG_LF?DS73hl#*H`{S?9v?r9pM^dL{o5+*qONOQMaeub?@e|hQAy)EF`L87?C+?= z=;);Oduf{Y^Iv^+clP4*$VS7iocTtCQ3c9hY0)$(G9}zZs=(j!&taXT^5@FlE-~nH z@zRr5s?1F?r3F%+%|>(I(prDVP;7Ror&>~c?{-kWRhPB6tkaz6=F2-yHxB>o?bz++ z$hX}3yU^Hv+Gb@dX4`Hdl$(@4%t#3EUvuz)iqBeCY*I1W~p_JPIIP3^2sJX*a1LV7ne7Llt4% z!F{|xAAPn?M!Z(P`*YkukCJGtg2UHRiNMZI%a0s+FkG)5LydzQqVa=6dZHB z#J_;43Nqg1=^E-o77WYaI^}*{ z>8)e1Uq4V7qq)uX0l!=2`S9n41o=SV?-@@e~;XhIl|V zx2%-*ag|xf!@lQ1w^*!=R%G%*{#98X^R=nBbIx!UVD|gC*@^${l(S6}(fhRkzxRxl z4=ALYZ5;9#Y$22%Png|T58y+177R`J4DM#gWi?s3z&^SLe=7{;)_u7UkdzVHK+Ea+ z$d|n|vsbbDn|rxY;bTSHc{HX=*XJ|mE-XDOzc~Bm=p}Na^EGSjZh(WoU(Y@M<*dJl ztY_td`=z;hY0UfD;{BO#h+w<@v*!J%S36^^n5RSkWml@*@l$EzcH8SEeT8VDwfoT& zwvdq1yZLfX;14Ja>(5l>;|aLR@p2r)iGugNd0We;)W#8fi>|)jv)KDI&60Bn+s^e3 zgG}~|{!3K7{KB2Sv_$mmgGk$ZQ#DV{{YD)h?sz-ik1M|1{;d`%+xiio1z2{nPr`N) zAMfY-dzR|A6gKqnXVs2yXFSHs;iG+l_g5$Lk26xJVJ5uvn9l**m%XL+i07t1;Jz3}90y72hYK z8Qj9e0s*g9)!jVGDM;D;z}UR=RNY79DAU}WZeyi5vou-%4V`T+YtcV?^(MS+BrR>G zj@yNIREtaL^-ngP#UG;ce$ihttp#fEQui#5r-g?LQetv{wdfNUGA2sclASM$Hk_m~ zg;y$rTsJj4hBI?rYOB0k&6oJ-Ub_6BxvUe$w8r;UGqdK5NOKQlwcbs{BlK1@CxN9M z^qjB4nICWU7yUrx*I=(#-S;tR=oHL5X8WY+-GkJ_oO_?1h!$Xw0krB8lVZ)rUf|;* zt1ESF1A<=FWq!6^hp?w9T^kJ>GFt8NruVan_VaobFqI0hsYTi`c7F~c;R!5#eDDj| zkGZk*2P3JN0Ij_2#x*mztuY z?%f=lBFGs@T8=KM7XMuHnXbIq+_{0k z$p(YRV!w6K<&3Y++pu!kd6o)ER@}w*k2wsx&x1DJ0~ZyS%QwCHE)G5~($+M+AKUAB zj#~pp-(0nv;D1mZ?jJdnC3&tTH!N#9c!_o1E8AMdnZ2viFW~!@FSkIk^Cueosr$oC z7p)t0TRzz~bAd3%{@Yk)V0t6j`PJ9Ghc9|e4OWONoSh?%Ewsce_fp`@Qypp4O6qadunz z83@KJQLU0;%lxIvnPB|2Q(d>zl3~i+-Bv^>Z?ED~dL|swbwM_#=g^T$5 ze#{gCvfHlrd7fPQ(+?h3#wm3IVl28cc70_swWg!0Lt^}1R#brv=c=nMa=lqUP8}1O znXEF=9C^CZ)Vf+}ZT(_DAYI~~^)nMqh#;Q*+{!3TVdW=07Y4{2qn;Xr1&$_OkU&%Q zq8Wx$Uuw-ZHj2ctBCT|^`6wCC(P*`KsIa+e#eD>ksPf|ga~Ao5&A0hsEh%H1nhT4n zUa@g&BpCjt2&Cr2&aC*`yI}q;eAnYN{ED8YtGwhctAknPhv{!fy!3EVidHV3Y?`0! z`qQ4Q#m^dgw>J%kq*4*ZqrGvVcu_9=oHHCJC96WsGskzh`I1$yHMo z$_T?ovQvM#Tsce2>li<~P_yxs&!0CaBYcw zb(K!M<|-{5JJbfmcSO>FVHFWJz!Lr{nJ6iPUJn34WR0P$Gk{{WB}ob7xjj+~cmt%B z9pNE~?w?)>ey3b{Cu802${HqFNJ((tYYuF|ZxCoX2)>X8=zT;vs7sP~5TsCcBHX^n ziip0VxH<5sur2+3IU2_n@Y9gA;DIF(+^sMP5U5J@*8s&Jy?Jn|e5+9rqG*w6VZu{# zf&18pvhpeiFgm9bXo|QH)*ew}q63Hzs&4>^%wzBlVam}wg8h8_9+F4Dz+;#@G8FR> z5zUqthZv{*J^VAlidSDnFou_)E(zCF1)o{01iS}0W1;jvG)rK*8FQGvcuOM+cz(78 zhMs>Y+rX&Ju}p*Z0u@~WtH%hd61X7ym<~aiXmh-yc_E?@F!n(2<9}QS$^zWEL_;L8 zq9v4wgF@Mg?50fK4Pl_^0DcjyL#EpVGw3HN%{x3t{&_qq><0p2oCJjpWb~{DUe}F@ zf%?fsF|4d=1D^Q05Hb zb9b(S=i3$QDSawPfBGE-e?h?KqaQ@?RCs&d znxCEd#>mTOcRXe+dl%KN>NSdT-1oF~JoiFr_WZbm@{#y)PBy!A)jb5>CjwSM7E+lK z-*!P%J@aL!EC0NW@*t4yc(3Z7Nu1);_1Jo?rl)%V`rKF+A4g8=(x0C3wJGQy^T{c= zExbA*>d$|B)POdBzjJgsy{fxgl@HjV#Aw3yv-^8I~X zCjX_KVZ(Ui$;avRQ9y#l$NJI6r}?hYXLcNeZo{b9V3}vBdOGI)Zp`Vu-L~=Y!}fhu zlVMs+CA)?vyOywBf2daDZAsxz!`X@ZV)e&UU3+*wC?YY!cN+k*TT)8(A&%$*%^8dY$dmBnBulRz}M zrjO}euk+y*>65S(3he7z?h~|Vrm$M(C_{c6(ph>=o6oo|Fct}xs~TE!egj^(svg|S zTXss8OJ@_3YB?{y{j`1L%XC$MP6&_bd@LD&KVvIXckxzy7%#NWq zs5)CHV3AL`a$x7-lNJCqgxapL$i5+BdVdl_(krz&P+YaYZ4>(azy~yRT#SaNwZy6= z4GEUFRk%-7u`SBl(djl>MwF#piWU!`SE-h8jY%Hraj4k8<}NuXdGa*D?mJsop#|or zQZn1Ejfh-!75c5^V_^ns9D!riGD00TMrhzy@r?EB0TH>uz3=V4|d6B{(%j|*{Xxsxk zU9RzJ0UiHV_a-}4`3)=Ppy4bn1+ysqC7K3rP3OE!=TKo6yE6-vIGtZQ#ijzZycIoYoQ>!wWE^VLSnii|B zY#+49u&6&N*J|--@zd-KIbmVfR2A!dGox6XT#;uJJD^4GX3qL-ueJu07~PE;qn_)? zA}#aeC(DMqOB)%(tRhlu^2#{Euy&1STvNFH8AH1s73)DF{7+2gp9g+GCK{gK){@)^ zn_7d826dViEr2mWzD4MYwIOKvlY{AS+L*iXnF)$Wu5mC{+5vBYo4O z@}#LBbgpX1Y-nyItw5hLo{EfC=sK9#!JPZgRBA#OYi`_GDL%BwRh+GztZ2nDKdoza zk|BF(9M8q_bfUiPL2j-M6jL=rY4hyM|Ge|K%yaB7f-?%I3=x9CMgk1=05`riJsiY3ZVbFz@CU*&d{uD_4Q+ee=Dzs&A&<@Q2YIkV z+PMHs*<3L~L0IenFmW(UFie9nwHkjgX-S1PrgP2>zr5*6b|^wY+NvM}0Qe=?z$PfE znG>u5<1bh*6^+gnB5J^wumJg2*j4WoVjFAE;bUg)P}NY}9hx6Yqd3C)gpMXa8fwqumh9NmH=LOX;|u}+fh{LEu~e-cWy>@f!F%v|t`?hM?5S_dE9^$;EpOvdJd47hM{a%LY^Ey=FXLgogmXTNd zcI|lo?}|r`Axm!|*}3_$`#$IQ)(3hfD6lx?EmU6M7BO-0v-y(yIS10|Q3w@fBW$SB zI(z0)C7amJzo(vhux%10EqZ|GXIp#D}fInl9InQB&e_DTJgkp&vL0tp|Y_rXE7v)&SA;a z(%V|be#`e*D^TK!Ki=+bEthpNUB$tAs;SSqHc4k&y5h?11g^3eQZ6*q+JFuPNuYs+ z>>F%K6ld?}slhcHGl@HKW%1`dxV=8!X{eWX`|I#L&iN&-tTkwzJ&CYI@Ub~S)f2}K z)CC_nW2H8wYd5f0t#Hz{HiESW1=o+BC0chtoV82Kk5vW-FO(&!sE%23p0UCL#v&%g zFx_D9gq!?%$phU0i*_36;8lb4jboFzC^@R7bmfa0&R_jmiJHE8W7F@t+_nh@FigQh zb*r-U>Q*4sx)Xi#Le;(cT5pn&^9&T$Y9SLo4JwsM%us` zhiP}BeNPpEBFC~BH$!SNBV(K)`Om7ZnA(_^q*G z2H)>a^Gl|KXmv~f+$RT5Hex>NKD2Bb<*Gl(hM&QMUVlwim!{xRWtRO+qBVC{P*c|< zT&n(fVROGAnkd!KUOK(MQtmW;SJzkey7|4Z_)zZEIdLO4H+T2ZzXgogv|o`oMKEpt z&?VWSCVEtrR>hz0KS-dePLv(lcy#zt&QYC{(%3c1jnD}e(P;uahe;lJ*uU^#vz*X*bzj@f_CHT={K~+hzOece12PvZaK4Chl=49kh#mXiE08@aubKtY#*i=(HGp(OhCMmCNUWd}vxW z`M$UzGpHK=yW%a9_qFq<_#X0Ulwnq)z=onl8AaX_X31QYX+E9lZ`@JY#>C9?p8{*j zi?dO>)@PR;j7v?Og_$mU^4cj=TNHI!7gp$HRoRcx4M$(Ggt)c@0Yj zS2^Vs8aet1YRg+lnU1?eC9E)BmjVC7&8D1G4u%%z`=TxGLS5UmX;s@cHKNx0fVTVm zs~I|?57>>D9h5horw2PAId-!uA@!6Ruz**a?v@bwRyYSss}KB#uq13lKeNr3mRcPL zvxC0^e;0d=FDao(QsLpo2RH!d0VC=G7$99kF=D|l{_Y{lfwgS6j|28^#jGc$k+1`eJM&dk{+jTqK9Qz%Zvn&gT8-6QF4!cz2AX zp9@5`XsSDAg_vgpb0XM2L?opM5+abnDDJ@2f?ncbYp@=WPX2szR$Ro}yoM=8@P(fi z=O!k8^fM{Q6%dvb!<|*;IEbZ)lWcjZdGnY{-`u~PJG8SB-VVz0m6%ngH)RxWKtjcP zP+x8)u{*$5R~gMkTouzkRso^@gQN<(T;FqF*1Ic2j_zmL;XLQ4V&Xu3K?2WG8eDXk z<_L6%MDjxNMF3}fP9fSq@Lq;FB}Um3%p|e;O&D^U1|(`iiNz8&?_nQG2oNK_Fqm|V zYEW7G|5Z#^ld~EMQ-F8L&X;M*9vFXOx_u>&^Y_e(I za7jn7>4o8iAA{T3TolBabh-o}Gzy*DG>f``i}20u3>&t?Sk`_7}n5PVHeSok4_VVU(R~jZ3xN-?p#= zri_Vd`5T+GK(E%Gmv(#2sfQ`=kAcpAFD`4LTsQ60yLua5Y)%s{E|fTYwOg!%?A91< zwVO<}yR`R%lJzR)JbL;ty{ml^@8*E{GtpA!T~3!VK3*&SsMPX zDtFkRW7!Ud5|mn!HqsGbIWPhZoKsm5mmON1K3hXeDabU69p$Yy#=OZFSEmh)jXWz=(RZB~?ZGTdEXyG8S9XDhKt%>_+UKptcv!-LMn6h-KEb}fZ_HHWI z^X^E(2Pb_=j6N}1D&GUNi4uvsZ%&`$RNpL(AuY%}vJE5a;2%un>T*}e9xQvJ@Z4`nF8f}!J zp0PRYJ%%dY8O7@_OZ?@802i-qLF{Qn1m4w2UPy0xXlvN^7K!Z$Z);VNu_dI3cIRs_ zr+_~Gv4H#iwp9vU+wK=ry!KJ-^~N{6c`Ds%cQju!^KzHY!8C763%9)-g2^@%8m_Z7 z_mzK#vI|5d;yhzx$YtO(_K<}i;S;IEmhZ-|4kOW()fO0}d#kt8H4j$)9bl#CVy(7Q z$zK9rgTWNql=8}4ln=?C3yr*n(7n&eY4S zwu3Oifq|;Gy{?{3w)6_y0kg<}3ep6nr<{U`(}F7X`{k9~8OE2~xp0YuTd`i??b`q1 zB6ZQ5_kt&bdro9-50vt*D_Z&-Gnd)t_|Gw74XWX(5u{9bL z?pRpq4urk^xsu^1bHAH4S{poSzpm~DeZmCxZvZ2rS$Z8RHpXOhujkvt`F5R7(-um% zjyi>=I`@n+Zb~xt&u;`jnYPp{kX;v}9n|<2?FzZ@B3i|s<4l32aqthk`xiJQR8rJL zB`Fgnv6_lZY~@BqgR7`andmn9QpE&42+C@oMKnxmA>Kc!8IrzmCAwN*#BJ)8wqr9@ znhgj7}38#RbM-0E*Wy8by1PzaBtwZ=vgIbQ{ zzXDk5Hb1NGHWQS;aTQXcOUsI4q-!X8I;e$}w$=u1X5kdNPX5^enTu^PRsK^=SF)>4 zQ#u_54s4+*or6k#Go;V2uN|`9NX)fePVn5##H{Z^=wJK2m7;8cuC~|u58@2g|6egX zhyw*OqU>-w86*7&1ZoTEQGtb{9@?WEgXL^%r6jTX!c`pme%FEAx9`AkQM7I8!hV)Q zp@Q%YTvP>P?!m@XBbf(R1RK(rLdx-{q3Q|q0u=fxosU4qesyxTz6@aB4G^bcz~}8^ z+Dej{OTM}FGd)uyz|n0=MnK~jAZJpcP(ijJkf1n24u(=hbX9w7oDurlLCtPwG{q)2 z?dpa9z;$*Y)XL5!Vnj56!7pHlz2>(TfdwOZ0k4r%z{$PG6ZSgpZ$y<1QiKN!(WW!4 zgH4*%yPTV(scPw4Q1}GPD1nR(v1wp|0!l7p0Z?5naaUzNYIHR!zzaAj`Ib1%2o;g{ zAUI7BTNK=9V+pY%E_EarR>zl>QOsMAMe})ILhg=b+ec#Pb6;s*n5uNlKA0F<+h8e9v1Z)1O(MypnlY z4TCLc2lIN=NY!`PzCcBsIfba%@H$5xbI7hA=P^u`UuF^`v=0utT9n`iD(iRKo?Cd_ zUAF%pTW|f;*86?&1`RDmS_%{|0&Zj&LE04*1yJt)H6QWGY@Kr=~v$d25ZaT;sj9{-wJ?r^6aE+poG(bIq!o@eUUq;ig#m3?t*RGFmJi}#N38weB>1jb(RF)BNHVt zoYkNtJ+rs|P?2e4FNd>yX=>O6JoXTRAxY(x+Rv$ii|bnb+?e!0KFMs#oth-3o94!RvM(`RG*NAX7%hq&M2i^O@ zb4;qZ37L4<7fkQ{)fVqAQK>)&DB)b%Vv*FL-20)kp^|9~oKR14p91a08mC|58I2YD zd#|g+_&d7z;6Wy#p8IHv0hy7l;LcS;*JpWBreS9Hd91VXSiV1;@2T|Yv{+F+N7i59Dgnq4qv4&Uq}LMV#{j^T~L2eaMlDyT}4I* z53Smd?J;vAy52$Me`sYYKCf7ZokzA1Y<>hQ%-+TPmzklQlpLvhD9vAO@;H=@KAcwG zg`4M=jPyu4fb~9Yc}0IzM5v0i00(|?d-~mTrLrBeTfN| zE}|Xnky+nh-*Jtp%CfEbk4A$+Y2lkWAx8O>5B}aeVr;0ej6Kl7JoRZ5F#ont+yZUww4rWl!1cfsI%MMA-GpiqUMxZGs~91DlZZVxY+`; zj!Y#le%r5(K6M)S7|$OF@YCO9`lxV(6rNrREf*S69kC5^Qiu<=lPx5PEqzx)E^WDy>ucBQZ0^$Rt6{;Z&oWwrs>JS1&m`oDD)4@WIo_%5$`6_cgfk?~hJONK`=ki?MLGm*-pw-9l^ogUz5hOj0r)#c| zq<{M3s{3zuj2-FbzJ)@S;r@XfakG&-SJS)F+zk(xd;dB7i$R;akcL65t-v*l#|xj9 z*@u;_?SJs4ylDqW%c$p79b(RD@ssWEZ^TaY8~CfH&3|aOy=iIPgM?rVZ#%x#WC5nAK(Gz+MyCWyr(<&Ry@-_zl!%zxZlR5rVhZH&>?1NNFc~ z84^gn-QW~hg+DANeW;|+-UTPRNaOU&Z`U%hIp{XZ`ktin(3V=-?Z3W4l3W*Rw2YsnJ^$B|2d~kgUaP{E z$7F(AQ?vEQ=0aDCE^6IVyHI;7kzkuu_ai-;Wxx8Sw*=p3Wpn-vUu-`&9}}YQB|CH% z`7H`h-Qt;`RHF_m2!Uo-F4g3h#Uek;A@pl+ z6qOcHwQlbPhCSaN4J^ZRURQu&nzKTEvG)G5sk3|hXYpZ8)Z5oxlBgK40D8~EVcDr- ztgL+AL8wdT<9%=#w12w1T3FWB&~eSm};ZC+g@&&_N4^>}1E zfhe?#x5bLdpDW0^snqLu1uX?FTid5JRbAu+pZTXK>m)C>R1A7b&ugZ@e4id@yhvo+ zyuw8uRWrjI@)lweidk4X=l__EYq}zedOTEG`jf`pnI?Q0Ih^gCWqZprkPSJ>r0Q!3 znn>kA7ICrCnFHv%22D^}I_hqtk?d-ix!y*FB+-3tAgC{^q$X$jZVDgN?5A?BJ7m8~ zqZ!%enM$U#RWnn*%U1maNSu7*Jn5B}xHAs?_iI@=nqE`;2vm+5CM4kN6XfB!wx_$@4T4 z6fo<#8KD}s3t7mAuGd!P%D^8C1TH^rn~Ms(@uC4100!irHKI6qqsCx&Nqs$m>RLm2 zfO{jBOTVz+fqoxh`;!9aJ3qg)g)Ds}M&{>^KBJK?>+`%IxW#U_CArKKI4rKZz}gKC zO^S6Y$|qvUGm!zVnU) zKsfq`M_7|+GcFgr1K~{S7E)uM40lJz))Dq4T?_1CR>Z%jRz?0twEdIHu3z3{^g&H^ z?sMiZ-bq=JUuejTC>8*`#qUlF7VV-&)XVP>RTlysEr|}KgRaWgVOKk?HV<%{o$Z_l zEt~Yd4ByyHt0j_-V<5jo-{U%m$Jh2_apoBxe<)`YeI7o?$x+L8PPpl!#oUn?X2pbS zS=vX>R@J`aR?YXT5nj*UhT9zI)-`<-4J7?^O*%Tk#Eljx^H`f9_c-fL6n2_E7W9LE zQzgV*`fB)I)?v=y<7~;_bGp4RYjt*p{WvX#+IRE}B=RZ2*6rWPzol#Bl`Z#in&)Uc zkuciM?Gq8LIL{H)7G@y4{l0YJ{}!w$t_RunlRHJ~!S&6Y)Y6HOfM8>nrob0j=a@z= zr%|3)E!#VH_y<_4LL<726R*I(2_h9iSW3jnQ~Tw*I~Cb>_8SC^hWZ+8%Q~%-G}6`R zgpf~0+u8ng?I+nKsT~`s9{r)@JH1y4J}8Rqius+gs8-XGl?A(+C*-bkar9<8yBI&` z+OU1c(7#UX(LwCCW#p-38kUh~sBj@xde=WEUac-g5==(?oHVFK6i8pLNqcIFd44du z9DiiGAM9#Lxzg}j7Jq2%j~5myC_-f?n~A+FBdeU1_fxF0G`ZB1zyJMLwu;75XL2B8 zLwAyeLztPjjG&LZW{j@2F$HLmwhgCsOQori*fx;x;Vk=IYpBt=QJ#A}IdD^<-+uV1 z@6v>A%1yE+$DzUrjcRBQUr{O^)r~u5=~}~oYoo!qSN_cx(iZ)Mk3eJSGX;$4VkAkG zLyZ3Im&}K`<5w3|{XF}p{eszNX2Y&q>J&>}{)PVb+dEz8cj5~szB zy7QN&vww;m-5b}hr>Z!Geh4_!h+sgq9Xn#oa&{5V&gU*k;Y`M%fY;?~3 z(>lOmEeRdEUpv7OUzZs{V?m!v&ve#AXT5~h%9aXJM1>IBgXXrZ>;KcF-}jO!w=^id^> zyvb3zuVoa@wgNZnvHwg$w& z0e`!9EIn<)Y@)88vrc(`K@70_=CRN6K2f1RF&>Y4oc z&BwhVF(W&D^k5^&`dS4XbPX->!Z@>j>c*fYHR-6qDX;qsmLVgt{B*W!+lL{Mr_kLF zY0XrVLe;<(Ec6U;Y2S3I3jVMzExG@w(}dZg*0ePTl^hUu+uVq01bGjkdrOuA zhKQQt6XUC4)vi(Ybx|M1lh0tLVYmQNm0C9v(Q8tUSr@tbe+ON;2wl7t?;3PiTL zO`Z9T>B7Wkn*2IZMa2Y?g4KyJ-fv7_Bf>Ag*AfXvGSdIizTmI|yljc(yr93w*eQr* z27d0%X&PHPS&ZN{v>}3Gnyb^@P#EkzS=V++=K2K3Oz5HOL3kfnGV7beI9CJcC9Z8n z0>AjPWY$SCN7d!4>^&`BjTO(Q>sJ)^AjIIb>+j>6llR-RcH$Oj8RpvpTxxQ9t{c;W zws@9>ti>g;w;fbX;$m#D@CX4ipMfj>b0cC?7~<&t*^z*hpoi_8E%tNqyY9}fckJgm zrgV$3o~`J;%Eh2ct0jxYPjPTkfVur`8f0axb-~Z)cUKok<^7Kj;O)NH?i-JdoqXjo zkJyfYjhz|fez%3&aDE@*GhFW)@sjx?#Po;Rb`qlIyJ1-3Bi%#V!|br?r~4z?U!4qT zIW#ScG~wKChW*drP4lb3Z2iR)|HtKJT7s>yPu{>si^TOl*MP0NvTs@Q^IwPm&p0qC z%U767`l`Td_~vLcntTwSQ+QdwyUuuN*Jf66X_u=uwd7-#e`Tuuth}Ql=`FL$e7F_g zqMKxC;{I&7ucqQdeah3OuMjJn79AU!Dv!M6)eKI-WAkhCKZ+aYIkygCkCWST__MQn zo@mOZy4RJqfwg7H-IAdJsEfMP6ZesEF5{kXNc%ryzxZMCZP9G^ly=)3uWEz+>hw1i zGzMBC^+hpXxSEQB+`jxeNWhh`9l|{I8>aDW6JIdJAEYYFW~<2L5-F3{GKA2Q1p?ar z+VY(OEO*JKz8Ku-SZC(p8IM#c3OF>y0miNjwCZE;s zC4IE__k~5u^5HX*b2Ml>*y3RidQYl&Pbyp+T53WUGm81Pd%nCLw|BB)pXHl!+gG7v z8WMf$+==B^)q}wDgS1z}^D{=~oF$t)Uk+lhbtrhLCyz(&b%!;iVAa<-Q4=jvC7@IVTR_?)2j!XKFlXCCus~ciI z-cxDsSI$-ZZmI2EL>3CI+Ju#ZbG+1KqCeckchfNBwa*Z)`X)7 z;3HEO!?*Avt>07dW7K5j>x#1vIrXQFYv(*eLxW&zZv_&OGryat0>9px!*Q;5OAr|N zs8^W$&He=@%rCIYnceOYqzgG@Nj>xKOP4o#UoC$0msBTbmg4#%LWaXlBFOq6^jfS4kDywZwAVec>66E5dOXs zxu$PJf9#reCN}>o+0Njsa5NWIbE_!Z@GveGd(Y$S{vFA1s7_CvpV0Oy zI6$=xDC^Jd79|eK_`NvvBG+2jXS2EfNFu~|RYE$SspcVUy`HJ{Awk2Qf0Z5I-Q8;2 zEptI#%THczH(UMbPr|`oCw^BsPC%eMefHUq((KKW(9m&?rlsyD{MG^{e9(-e-Sr?d z!W$I7=zloJIrK0F%aB?Ms$$}51?2`j-aZ*CW~z>FAMpqMd4B-^lWrcSh3i}`;7iRt zN%CDZwkHh^O4EWbf*ArcZ1_%=yx&#wSG5}r>V~t{505&l4 zAOiGVSjaeWY%BUa%ncVJX6)~XBg8)S0Y)RhyXT@g;q039uhb27IOgc8vuJIY`yO@| zz`l&?FP2iFXcs{oa1r32MAyUV(e*qIEj>_O1)joyj%HqsJ0Y=ILjlj)KQYU;q#Ajp zvwZ_64Y}gM|6)NhGc(=o?8vzZ0bxsegb76Zf`E5{-(;zU-xlS^LcUH$i#HP{61Cf6 z`IbdpjmZ~nFXD;qdP82tMFq~#6%ho}qpUCRU7lC+k82P5vqfbQ@6ZC;uV_@X3KD$$ zG_B|HR2K`3JqpAIuTLn}W&tzt?;G2G*}t?U7k{tU^lnu+u}jorP2UIgG3SPO(BH6d zHt5j;;yXNb_V*=x%LuOq;75Pw%T9IER02F&3>4@{k2MqVm64CtTPlRMTF=LG?HiMs ziToEBecunfSTV}|{(A26*Kl-lK$Bq6vU8{w| z_C((#*sp6p-DVgG$+gHkd3#a^xi|!QZD+&xyMGmV$c!3MX;vRcAC8$WnV}QS!dF^k zAEAfu30s0%kIOzLFDyNfI04`;^UqhC%$A-kWlaI4zuRBT4p{x;sxe$oBWEzXoh|>`qAs3pjTVEXj&$mBisk3$I=o7muThOVHQ+P>BR8@4l49)VE^x=*d3!k# zPJ51cb$^+mAztb`EHnmIyqEopvpI@NhL2hwr(I8~sI+*?v?t5qG~7M1FoV6HMqc{U zRX;tAHQQ5aoEpl!#7eC>iscxqtSR~{cgd%i^(n-I+2)>XT)J<{bV2GP^DZX@T__}- z8bhn<<=~%^1Ml&_G4vGUtOxV2O>;Kcs$1@)%(VIT@wYL-8gPr@O6aAISRTmbTg7JG zl;M2q(%w>ynX5E|Vrv@wgD5x?R(d?e$6VJ$=hUPOu7Oc03UpbGs+XGIgBp0sI7P~) zFC%DM3sjtzw}ihv3APLo4kB+1#`w_h&YW8fy}{kl9Am7RA-y?Y>YRk9wb*9Gpfpr8 z1i~m)qkS$CG+Ev>IK!zbMeZ=Zzn}s4P)FWgFGmM{!5SLjxsSa*fkety8px(HW`DqR!{{Nh<8jl-U}VAIi(KpWXja z+`6FZ^eYa!-<)8bHlT#ks)1Xojh}{NzZk1x&~u$X@UK62-V8WTAGfW64qKWE0$7iV z;uM4`c^6DEYLWvqrK-)&M?FT;k7nz?`A(S+b&FrHY&+(1Mgho!3jX6#cUgOX&iO_z zZrHh}t&OBpEy;NVpPLB28cO5fwbFL8 z#gs;tWCWd`q)o5e_)vT9^QHH*zA>*0=3jRm_pABjX!7I;J<3+x9egsV*g5GG1K;Mh z7%BC|xiXPtc|@}2&n9*b^i*;*D!J*RpCXZE1f%`JLn=KzWIX<76z;+MeO8$a&Uy}Y z2X{@2?jFvl&_##w|D1fy6_k6EXEL<{;4r&6U9S%k;<*aU{Hbc92|DZ%23cWj#T&GW zBCx!t7aLS&7H^jy>!*peO(#dpij$=Q|Dj_y42p?rF#gB=^>h;N#fSORw_&w~_T1>~ zi>w&nu{>GCdPJ`lh$cecax&YP!3=o z22&`RWpnr0b@~}V*K8CQ0$g!0H}8?+MiQ=S;vM|$6Y~5X_tP&}9U_QAVri%^zsdOd zjTO*A>_IOUN7#*%h6q+GV&HPb{;&Ns+S%hIoIjr&DVeoT@)m92>5TbkO4j{i7r?69m7m?ksDWsa>IcFzEx8RGv+JN@2}dY?yu zI1Bn@f;l%z(cIgdPu0Wck?%CuFE$Qnf@tAQ*CMe`Fq#E{VP^S%(nhcG0*3-k$t~n> z%pT(j+sneeCgd;ZtU}QzDl&@z^RvWQa8d+}=DIdzozgSZf*3@q0rYc?^IeormJzCQ$xrx#jq81ybn9YXBSJIgC2GzN=wBzJLisjZ!f#A z@9E%6TkDwTLH~fXnO3xFHg0a?hj7H-pjI-!4T7puW-gEA`&j;zUXg+k5tG>wS~wzh zk@4WjgNm(zW_*=lrI<^E4FMFt6+j&Pj3T|S3A2d22 z2X$>%AMYw#KmFE0)r&}d)~@`MV6f>GiYCgfU39%&HhUk=L$a^|T4wtnK#lh-WG}H@FP)U`U#bS$yvENlM;$k7{qRmEpT7U9XM4AHz97dK>@@7rV7jt#|4i??G;SwBbcgVdDY4AY1t4=U(8W{p*vrKOJj2H^(9+JrAkh2$PW|^ z(uuYo`|U18Iv1o_^=T1J3`cc@S?#xec&R@hc0>q(b56UhL zGzMFtM@`8Kk@h#*-b5H%dA?(KOr!3h+@O8vNDow^SqKekFOVv`myJudxhSOqHzch5RdjQ!teu%8PfVHHMvL1&S;q>_AzVw7I$y>AzQ#V~C=?&_AS6ltAPJO%kbQPg8t`mniId2hbY`KTs`O(#hvH&OF0 z`93R%^4*HxZpB^FrP;Uu&%M%}RzFVCDZ2^FzCNhcn7Val?StXqWztC6e>z%9ReFmk zZyBPd)5_kIKh6^TqoaA@1??XSU zwEQS$NlI2GO^zU?Ze-)YW>wbRP}b4TfwBlJs+o1zdBT!o1!$TFIC-Hzn~-B2Mr^Zu zCgnmVr*^8R&x*=^TS`TgXMGrhHf#*YVv%q13sE#*oku-T%`Sa4?-6}YU)7iHcd7hMWmb|de(%OffiMglPAL;*@ z3|m1BX2OrZY#WR4tV=E}4F9mMiDnIi6}SA^o8zlVTZ|n!g86x|d~nU)@;0iPnZIVX zf7Rj!w_b8x>@@hug$<5nqA&7?zWUUr)&n*$Gfv}&ego_EhXUR;W-tWeT>zXH@NrCm zY0svS_`!7B^hJQ3_>>RKU~o3x_09Yt!eY!Pn+`m>^V9vwFkv)t{c zH+_7_K6IQ{0Tvpt%}iB`V~YJ(9q7nJpf;Pa4@ zmsHmy^E_YbN#jwupb7DOdt)aNsMLA>AR{sMD9QVl;?gZ!Y`W)+Xv6RLi74_8j6 z%lByN2)cj%%A$vMh&7A%hDx|IxiJ9>;W3Kdf=B;c7ybLDjfkUwbaw{r>+f@lD>D0K z=ig;4{0?!E)o_8CDKLT#R5j@sV4VN|XXu3z&k~kQxq&uTE*v=KFO6W_xzmcA{}_#Yt{8-OE=57pU9FU`%Dv(D4;D^fAvFf@0qqp>7g%m~63*W=)_ z@1?Vwr9%9z0*J9+;6-9gN*~9-A^@-NF>iDxhu(qrwy(h}HTt(YMp~NeFZXAg_F5`3 zdh3O)7DV<{uD$A3L+k)R7Lt`IF1UbMPN{L_4#c=MUAHh^x7}ESAkD_n;TGlHf~Y9Z zfR!?!HW(nX*?F&^e5svF=)mO?==@DsLp?a~S1lYI`}f%c z3rOaSE6wft`~o?Ei+blA%)Ht|-r8(>a~i6b=3l7|F?CVMH;sG_F{lhN->Q=5(UISL zZ{F4{nd>Hl^6X*uc8*GpDh$;zpuS+q_u3P{e>xN~ReR8{5icIZOPj*d zFj$Lqpc)I#@CSmlZ5$flX=LUnZh{)|Bxk?mOdV_R3bq>6jJq0AAFZTmoL}PBQlL>> zX3kL>GPJ&1US@nP;(CuBc>LUXi)3lPOYW>TUp(W4aU9n-yfS=>##pnJzVR^WL@PQ^ zJ9nC=)}Iovxi9^w-5)dgD(zvyk#u{GaOsqYx;PESVZKgM&hkUA^%Vu1NXQ(~v+scF0RZ20Bko)txy- zilo@&S1ZrSRRPa#K6T-qV7QzLkn3S3F>nBYaj!s87|jr!E~b^2arirA)nEF=9;z{i zYPYbSDoz|$bEx*4I3ONg7S@9r5d_~w*7r!P>w(k#h3GS>XLcA8lJA%B{}Ks4WnSdb z7+}0aB<6OGZET8f=Fx5IA@b>nVfoJFu zqA33`zm>!8jWn7ja2JdOD1_;RTm<4RmE~Tn^4JLy_Jy`d@*$as>^|uMzvK61dK^%E zBUT98PU;hKEPZjNMg&Oo(j;;OuwpU=dk@k;@ml`y_zG?btx!DYFv3{OpQ7-dqRp1;n-3H0gMjdVnGJ)N?t+6kg5qg37-d-%R2kl<7iJG{|Z>J`4d zJD>b}krm}E!smj)@g!pDiws{+vUtG`E@}SWGU2x`bXDa8C$ab^&rxCKLoGjFu?Lrx z4*Nl6M0BUPY6Mf&QFRQ>82e$X_EG*0l_8l9Q{&T^c*LIqN@1>=c7JePl)S+*gKW z6NU^xBnxkYtA@-?2*C0a=x?wG1chPPp?IITufD4DR7-L_lOf(Y!0HeXB_aa%f`h5{ zbWk*-2gxaax+XmKZ`XI)0dTM0If$a|;+*MtHK9?a%dg&XBI4(R?p=H>WyW6m*&(|Y zhP4TD;sWZVc3h~MO|BH!r!h$Zo{(U-J206 zGjDY__Yg)|;y>hJ>oZ`llbV&uG3Nfv7^4eoW2zF`uj@Vf6SkDa#;tCCzP>_>O>CE; zbwIhluU(r3p6!@OoOWQg)k(f~-y;&K&~a38tbW{Pf5`e7yrd^ctH@{zO6RB>rUhdm z5RNLQ(bKj~+BMfSckX#(IaS14$xvqneicc9qRBTIv{*M)`Cm*nuOy{x%JM?+j|-mj zFTbprOf}gBPKW}ED2SJyD~C65 z9m!b8itD@i+|Fu(f;2%kxqy_kr1A-+u4rt{KT~@9wR-JsE}cNOW^jmQKTba$Swh9{ z_2+98H#~;UR7hE2g+7qNA4-MaY{)-P^+jpL*kRnemMAUNq)cdfW-#P9uPCwXcp(tO zr~fADmHV?^GL1;i6=N#TgtQ@6F->**`ofK+crq`v!ojmFz_~_iJ*$$XR)$J{W=y7K z@+|nqo746IA(U7~R;^-xb@ttQDZzuAE6`EnwEg9_IaOw+Mu2_K__6v$h0&wLQ`=r$ zyR6W(&*u?dBFoZ}ph$2EYh;2O#EV{4O9#1|X=7?d+!a!4P(R@fMSl9wOdFY|8OHKraj9 zH$<@rXC^M@jD@Rl4wJ9|>n%1jP8{YIAjF3*PyFlzP8K+t93UwOp?v!s(!+P;ssv(h zw*~9bITEh^*M&FpBge4RXy*rE5yp6^r`mgAGe$XsV8;zv-Mx2orZFEZ>e39Hxf%zh zy$xN1(~@NA80c#;-?`EGd={yF{bC{!R}A1h*_}4})lgb~F0!MDQNnRc7!ob~hGB(c zeem}A?yl;%>yuo6%t9_^_uk@744dy~#rsM8gW{p0LX+}v{_(FrN$qAWSjhK)wieVo zB1i^~UE*PkgdG{0BvpgvVIHe|5y=D|>9nXM)pYvF^{g{rLLU{M5+DAwd4pX1Bdmi@ zKj5T4Ez;qnTVnTis$=gZuIK|dq>p{6&6ck3cb+Oqp))i!oRP-VrZSXf^!;~_$FVDy z6Yt0S>(&p_J{KGUm1}Vgp|{VOeEd$j=P$19_W$7vH1hbybUdcocu;BUCCqpFNVblM z>rUj>o|9bfd=)S*)KuwIa{f1@cwt~Ozan=1Vu&kH3-jGlyGiF|R@6nwpAh3ad{tCz z&KUzbbQ%{ORbxOS{1n%eR|z*ppQ9h%XMHLnzJH+Nn%M4i9c)Qi@_l@k-N@S)vtVYk zO!YKKYr7Q`yz>NpJnp<7;K#k*;i_quR1KPs9$s_xza44$|K>JiC%AJqrVd99yP|yC z1Wz^oAx*v}GkGhQ>)Vx66KN@@9{dt5HG@^Fbd;0?zQ!`L-~Eo3dK)5iA^K$AL1Yvc z356ej!WOgi9n50mTG?W-({KW)@F1Pkp{ zW}Hmc$6o8yZ9=hKN5l>%xA$dJ4fl)%N7_#?v;9wR{D#v<$iXwPLxzq-3i)zR@S0UK z%5B9p4s4g^oarG@d~8Wgj1^Vc$QqioSKNk}lDr4GAMEKniFgl5d0M?FYJ1w|pnmyc zAKPp5-6dMgGbD1ZM1uHL+O#s(xyzSB!L;d0KOO5Y_i|$xVkmF$lo-ZYMRI+V;9O0O zEexhwh&+3NH@qt_g*b$wlKY`mPr$ETE9vOD<{%Q~UwnfDC8&9C~niv(pWBjZTs zU$HI1$?7a2<~IK2ViECmcs#DGeklPfjD!6c?}a*@F!S{9570K=7%u~fJQb^4EJ*uW z20C;z97-Fp6GckBzlm|`V$oah0pjo7_ldiAHL z_LOKV0<7PE=*xujfYi7dG1FW7Lf885#;@L_&Q;*g1ha9e5$$*L{H6LyPp6aIJ*4vo zW82tJKDGju9Ry~tP^S?T&|}}B_Pt=MvXZ+rco{_YkBgHR`GHY>se8`&pLRhHj zb6(6h87(cVY_UvT7^t^pPFTQnKdLLIrCv9An@{V)0BO*IV`^-%Q#48W7ks_xjhi{1 z_yi;7H&?ENy(a-y5i&sOdO^YdJy7_$lq| z9JP~GzI?mPkOMl1a}ZvHJ0lc2Z~dLs|I^VB`CPI4UYn~#YrsbNdBv(q<}>OUB>P3O z(HjdJ*Ur z%3&O&9pt8LY^hwnQ9sTPpGeOc?{E5M*>9^!ff{Y_zuBpOJ{JGY52~oEa?4ukMu^&E zIA>)lJzQ#3h!^t3$3L^+Q6%@S{&k}z)2je#G5<8{0P58m!|7)p($StXNQIY{BMnu$ z15`FY596HKTAnd|nR?~^oQz3ZKMfve_z+UM_US1+x9f-0?*zh=DhP4 zV=Q4q4ozpvF7{M6euxhv+3ujKWF_HXqv2qs_`+5fr^TC~C7Pr4j!ZXzzxr=Z5m_}G zYh6R-L5}B;iLSbRLHUA`!EQuXciTeF_qOz;ke2WE=N$@~Ld9P1U(dhPJwPOxPj9?# z5iMmo*%%cm4jTi3nA^@+OwvPzDAx#^k)It1K!zL|! zKZyh(RuBAr0w=}8e6vak!2z?pC94Jc^zZevx_JxT$2*7%!% z98Z=asXr$uuUgFisu>NiNFv~lk}G_QD9N^CK)7Vr*Ain>V$Rv(Ulx)d%IRL@iER`c z{sE54N$?Ohru&s;?n`oA4Pq=cFn?>*Ypb(y7~{Z>+fljwD^0bt?!s>Sao1MBJ-CA) zm^ScxOqNBlJP1iI7D$IFeo^c+CrP`wG%wNfgeo!Wab^#H|5sx$!BCc zr!fWoU4LUL|FkdiAH@5|x4=y9*bhyht(QYrh46=8>!g77+b1--^YV|3**xXY|Lj4S zCo@mf#q!;UUuPYgxU#~he2X^POPg6X&SS}{!m{M|yY1ut>*%`o9ZHqC_X#R9Rf&D# zWdk{``NogBj|Kj<4V77inhyi9wuf9XyD>nO9fo7Y-C2o8D)d)zdn>V%uNU&F;<6GK z33lzb!-?aiM0-;<_urR<(Ta<|Ktb?@yrWi$f&5W&V^YouI=(^Ui8FBjzp~KA8hK9P$6@N$ zv6D|8r#IU>2F$!m!T;rwt)(!@jWt4bn&^$glwsVZfC$L{-XKKrj|6RqR9w+lJ!+q&wtCF zWd6~Xs?yGum+X}}4rNxmDQt>PjtHHmBUIC`3gXmRomtIFdq-PrdtUnr0qBvOJdGjE zJ`IqcN=kFcZQ#p5LtAmmt`_V{i+ZDoAUnWl@zbyFHjH@3O1{hesqi9$@)#`fB+6le zy6r`W>6&TNW@xv9V!M^%G=}vQA3HCNWre{bDypNHD61G$V}Hr-rvlGI@$Y6_$hw4< z2xzehXmIh2zvb8JL)U^WW*a(oEMRFAEkD}yj#fkVOfAz_NC>ujBEb##OKR3tO|q~` zVAUd3g}CKnlYJmxSn%gJo3O=$X1)X5!wz&+upg|>)3`O%YN6i#%LLnVEo|Is!OC{T z5aZSaF*%saMe@z+8@<8y;9Z_uw%R9xcU^DWM60@OdnXg*yx3&jZt;UHx

Q0kfRjuOQSy7ea4(FKnF|z``cFYKpLjGZBVBcP{KYvL+n#ZfwV%x{>{OQNvkCW`A z{Gk^9{0`#$QKau7R@;%$mlme(h!+=o!ixOts5{JBr=m6^uExV9mojw0)bim#Wn%R{ zD%Cy3_a^7eSl)Nyqe&IB0f+5y&VEFwWX-=J_-=AdKxV_R|14MMoIcG}7~5V=b>&#Q zR0BTa;z@PjUKMXuI~e^dG7aGun3 z_9@qamngNigLo}eGDZy32e0aoIOZ2PzxZX}#;UMC0N0Ks)=fH3%81&+5nB`^2p|j4 z$Ad5%ejU_L&GoCmQk2XbJ$vrrHpDkA*!&t~fT0FqPr_iw{D2WGxb4gz7u5)%f{^(m z8R#}KVm|*b9-cfzqKohZHxK8njKH`$@P;L|Q4d)sPsG0YSyc?c*+m8+&I=u!6MZMK z^0HQ*a=c;5$aXV~k7obY^@U7`foK(BU>48`f4}_x#Hw!2 zR~xlb|A+N2@1tFChzrS_vM`zf57VYjp285A7itkkxGIK}#9Qm84IHJ4!+l-k+;b}R z{zB%BG}2t$Wl%5gz1j;vpV;_E>#Rb5yvt7mDu8#>EnzV~S=`wjYW%(3^Y%TwV=d6p zZaqR>0T!z0Q9oj4`E0${ABaX{MIoQZH3e#a`ci{-;$z)C)+x+~&;K8?&ib#(|NYye zOIkvZP((TeX=wrJZWtxqF}hn)X=#xhqkFVUca0n%4I?B5I_lp0{_*quAFk{1dYtF^ zd>%(q^c2k&GhDamXp-?_KM za9F#ZwC|}5Q|F~~){QfC5zP1Q=Bc^QA6bTu8^x1g)Eu%^`XS@A%?m^KG3bILu%Alg zu%}a+Pge9v;rP~)Nc)GV|{qhn_ZY5a19v3CPIvHz@qj0}x>I2HG-xU_lzBc~hW zeS@>FYO5dfLia!-;)%oCY_4iX!=I0z2wD#r@j{W;t!-x`|2Mo1yF9jaba~-%y=;FJ zLz7>fogdZ^Qn}Z>*R8v-3_ZF837!0G%d}H(&&4u?TNnFsXl+Oxm@enz7FHmA$7DZw zA1fds=+)rzzD23vR7>_0O@6sW;9=s^3?e!oXYfC<7Obg=Zm05MyVg>TZ;;T25^eH$ z{W)esZE1RkH>swOke#7zI$UF%PXt0<+6#h?HLaaaJ2jJXx(qKN6rfDdB4G&9%fu0kS+78SC8-$v!dZ z_!hh2Gb3tD3CW^gREB@(oLy5Ypm@eF6qB!GTeI$z}8-`O{V!v~o+ut^N?E*5dL0n(rSFe_cBZ5OepgltE?+>FI{M29Ot?p9c_4A zFhn4G!)kzNh_beOd%15|sY-QOCi3x{Syj!0qN;3NWpQ^&_4TW_Up3hC^7T2$b%hFB zHt=tGKFrTAHFL8Dx)bE&yeV*b`1h%HwDrbCV^2rlR>#&>kb{PR#@SpN$jtGtevAnt0a2?o|k6H=_g&V!ymgNRh$M}GWhBUXlCeOY*qy8!7H z!n?}-k`}p~H0u3KqOEoOJ=L!?r`I|c75m3+-UgW+@o>%M`?R}%;4buyOgDls=pDK^ zJF50NGbf&1tiuxYE90vwr)0Ws1kbFXZ>l9tI!Bq^g~|jCLwn*x`O^YTPNy64$!)=B zcvtZ`c{!Er9c_EC-(%yb(TU8Aya`U}OuflbF16C<@72yG+Ci5(b8{+_<0dAZQugBN z@2R@?#0TnDs^(jCRm?>ymKK^c(hR5A19pLUmja8YI;h5Om0s66>+G}X3aKki)F#iP zXyNH!SC8sEO9$hp z<=@ArIX^=S|3tHi)<+;2HgQGq9MF_mK>+Vv@~${D-Z17d!5oGOK%#vNGbvnT2PYr! z6QBv8!w$#J$9!iciED;=^_guP&*z(&3>i{~#F7}Fx*TU1;3v*$Hmb1;ok%70aDD{%@b&lu$1c|GLToA-_g!aanT~I zo2$r=Vnrbj!zTkvuf)9_cU6W4_1UMHbV<=XLlqt_G`kt9YC*o6-J?i@N_=2u7$PDf z(g?fIFN4(5?;l5)npG4X$`7(chh2&A zC%^gbT8dW~W0`Vwh2co6dio_+YKIZzL0a%tH{UzSBLvMSj9^0550#|;Q#QFCCmLlV z-6RcJ60GZ>`O!u8@v_TfobmTF4A?n$dwh!lsRv(hXy`%jU2)XGxySZ)%>j>u=a0 z2|A}oY4L^eT}f}i1mD5dARg#8s_o#W@anC(0{^Pb5a`aiXmN2LSjpD4e4TOM&^yc2 z^ZRSyY^t=m^g})qtgIrxM3)z;Y!Pu6%x5_zeW|BUkHb1Q2VM{~0sd-vQwSR`J1PKJgf z+@z{)Bb7g@np`zHy{c%24Lek&&03e0dc6e$8@`1$Tz`IYK}_7lKr9%Nu3+xfpZL~+ zL|+X>LIQ{mR|eGWTAHg3dZ@B=e>~#=@MXqf+=+sL4$AGN)KQuKObJZ;+zBUJt z20-9sLY>i@kTECwu_G!li5D^074M3Ucn**2#|kY8Mu^G3R;YoW$g-F7Un`!N+Xhoj zeynM_WUTiY>K3cpX{%RwPI%wd7uS0Z1%3MY;=ze|hsBK>AAc$@TKKwkXEq~coz#)X zxpV{iAS2Vd7R~!fjP$4@-&#Y;97Co$iXzM;GN5prRQ5ecQ zJU|BCht-9%T=|{!)77tRBta659!(f&$X+Q~)Fqjh^SG~G;mZQQOVX+S zT(MyIIg*8?WVBtgob!CTI4B)j6Xgc)@^TzO1(|0m&dF|gX@Pi~yIYejY!&pYtF@OZ zirXOxEuAJNemWdAIo#sx3mzd1IZJnh18Cg%uR_*zld98b{CcXq3Zq>NtTC8dc*$Aa z7+2kB9kZ{S%`j4B{gv}jhXR{X%fI%@tk_YSRh8Yb1be~+?hGM`!$VMAk7C{JiSrd+ zU580s7<`wG_iHUr5O1J4F}1r+qn4rH_iq;^71j3Jfpe3_Cm(o>I*DLev;MVvP9%RR z&pV8NrFj%LPAC<%{5dv0cV(n-%>tdP`~wq~%fBcxc$2R8=8GOjmJWw_Y~Zfmh%q8& z#^nBTv{rmhn}YQ|ybDwUxol*ACB86GUF~0%ht)s)o0HT{zV&0+b-$R>-&PTy-w7 zf~GE3N{a@`|8S2}>Kb-b8|hlX_G;%0+GV~==b$Y2o31V0Idr#aWt4RjSKIA-kRNBq zws?9$mRlQj?Q->!5c(Yxj14$%JJC9BL_7`oK0@#7^iZ>Sq{|dobZBHtY+p#2Hvt8lWlpA?^<>_vgopWe!lT0XPHZc~)O=O=Z* zJ;1p8j4LxBDWimM2e4Yhn+BMN`}A=x$3>Z|4EVD;hI)w2^^VI65G z)^Fb4yNfs(7T03wj?{+?W#f5_KBC*C%X+C%9PC(wp!q~#hQfM1Uxf2P{}S0emWcH! zM$-X3H*v!&?4&eYXW}!7 zAniR$>b%wcXkFD?>3ocL30<04R8!O?6-lM$3YrReg5f&8r3m`eo#UZ zbRSj}RY?b)5pX@$YaDT*#^(i*@@Ic5dr*D$pt*n2B}Bg0pnZlRpS;}%RHxll^d%nZ zk4Sus#ClKmni>=FUOz9B$N0szhdx8ktssiYJv6fLVlWl4^eG6mdN2Ie*Y914j4?&g zbb}3qtGzpo?hp0aI->b%KMn%oV+x0ZziICO`-1M_yX)>$l?<4EM0N8UhWt+5-} z*s&csXGRtkxET(tHZbgLJq&!7gkdDCqnuNRg%4h@PJHE z1Fl6Kv>a%&10k&zqBkX_F{RH_FW&z+H$m;NTgHo%yv9e^Db zULD(JQ3S%;bxZyR62d^(DH!Q&dGdqMOK{eG&cYKxB8(X0?ZYOkTW+~L&84f+7iy0i zcyZdl9-D5k8%Uo{52>s3t1XoE9Jz*FE1DziNHz+^CiQ z+dbBDU|A@s)P5qom{Bjb)Z33j#XGqVYVBP`vmqflsQusjIOXHv@JVM`!PGwR8N2L^>UZb3Fjv9mr1 zKP6M9L%a_n!Kjq&-h(xBWq6NfzOy}E{!k{N@>)sdmtjVH4M%~Akg?}yzC1dPyklwX zOOF=yfna;q1GB6qp3K?T$_N{70^Ro$tRX|Fs;Vn9I8Mc%Z6Wp%Vz-% zT~VJ0J{V;BYa@-6W4b-{uZ`&0Ff$>km)`oeEJAG>K(C(Czb>-NYRXmbeV=TXm#Anc zX1-LZQMMK+|M0PHZ~rxwagMG)p|s)F^Zom2D=?b-5D zqE_1{uHbB~`U*6s(rr^m;l5fkoL8&616s^Io;_wV{~p$}8-f~E8q(%4mT>19mS-ec zXRHpE;OEPzmzu?5XoX^8UXt~hJ0uUix%of?B(<_Y*P?#NaHp{g&d2!}aaoZoG#eKa z^hJ4de-p*i!!Y_hotqE@pghI;@t1!5%_e&^DEx()rf1B6B-NOtCB?2bE;B*3;02(j zJ{PMU!#7+toH?8%Y@hrHH!T_!`wRj*Ajkuz}$11kbw3tIv4nZ=V{0#r(;|cnx`Mo`|B5nU};UIY9fOT`=e)L}Y)$_bRVpd6C1;^R;F!}kO4(7be z@a$LE?{psTsE|fFq7K=ll^-ugQV#?l@2ub#5xpV#n3nGp$KDl_U}sA*^Q|!^#xNeX z?O9Pgei>)Ja9AC5MdvNYSX&~`|R5v zrw%k(6d%NqAo_26!17R4CiVPUwg)Q&Pdjw|7#`OBnj{k{AcFO`5OdMj3=fgQykX^q_oic$Cn#RaB6#;@#LvLZr56%g z$2lZ$KYziE>+A0J|BZNDPD;)JVe#*r`G)rMYiQ8_642|ARs7QUeS*2RjhperKh_o& zuA}$a3(0&{^bBBn`lSF1tTpKq7H^A|TInXz$0#JUY2Ne#D|uAE;PO~d2z;$Kwg-QC zIT37zhYL#P6bqP9M$;lHzf4q`a;~(@EWf`>O!HFZUS|{m-c~F3#pkx@e4vpEyy32e8L^?_wz#wIsZYkOzGXan-zU4 zfsP8U%z4Vy(MjLd{mtJ&{^XMEU?2g(rdEuH4U^TjP~IP|QGllguXR*O_0@?Xu2>6R z461Rro?{)&zFc_}o4%{U43J~9v5PDHvAUE9An2!YwvdrUoddG5(9-VM_uV+U#$^dq zk4hjoZEa~SV{7Df>mw%rx>&Q3T_aX4zZN3VzMfkM58kK|iYqg16ZhDx1!5oYh$ptx z_B!1Pu^H_kFX@kVk8=-Uyq4zn;?&vich*!UQ5ZMIuoAA+=iDcLN=Lr2;I^Pioc48~ zeoX_XnSNd-af?$sgd~60rp!c#p2ikI^Agi9Dj^-HCDPEt;WzL4d(sJ|pZz?XMY>;l z1(cGl2S(JZ;pBL+{VDvioBb# ziL}S5JePog-MfTQ9GT6uqyDrgAN)<;r<>;N<6_J;MB%@McCoHh7&7mBFzJ7GAvuh@POP_sdcyqr^3ez)&JPszz8M@oeF3WX?d7J*ME8O}EwF8DM+VssR$yyOpc z%)iRX2Lz==qDppMlfIv=H0|4-h}z%EP4suA8T#`6TnIK?fFP|#3)#}08hNB)UNaWe z4Yi{)wO#Sa-Vi=%L7&>ug}%b3l@GF(HWsHNH=UfBE0Zlbme2l~EsoG`eSH;2vJ=Bk zDic?lPPIFyo_V~?zT9N0W>mD|Zu&w>k3&j_qph?{a!73M1&w1BSyg9z>m-$^ahj>S z`-@#Okm{!rI3Ig_0GRjh=!purzNxaryMl*P!onj9^vOZ-laa}}gUY#&VpWFn+nRYb zv-57ENfkaZ`j%#8g_r3zIU>EA#TJ7{YJ(REJRkE*S!_neD>8D`*~O>~eKgI876;I( z7PE$eLW-ae8Z8zvQy;hX^KM60zlw}CN2CST_)kv$k|iIVnZtbQ*Mhl4IffsdvUMmW zs5Y8(8{iTyy{03Q=_+OtRex=Ro`zg%lx>Jt&C?&RAlTkM4lezFxp? z9&Q1&qpUkxn?DV5hCK04m)yIl3!CtCzP!d(C3UBC1UwBV z3n#26{EK}D_yAZX>-*qfj$=ju7aqY{!ngp~0yrSfcz6AhnUdig*vj~Q2^Yii9(c@5 zmT?ymY5>kttc2-A;bNBJC*6mXn{*rWfVZf)Ru45(F?&)Un<>d!&!R3fdG;uQpFQO+ zvw$E#;PK(mw6(xH62xz*AQ>{K2MO&-O&^u=(QTDZx9n<_mm4LS)4#|L>aF<@Ag;_;^yd0%~mU<8y})nbrfc*^vU zO?wh|e^ts*6_b&lontF4bKBzxh$vh8ZUG2AAWgE-G&cJ#HHd{j=Ktaa8SY+8mOuU! z#-D6)hZ|LkYgLl#FZ=t2*FN{hVfT(9cPvcvLvHtM-DgD)sQ)fue_1wG1X79nu)>K% zAP7e1KZ#_2f2#x?On-|rbHY&gmdCUB^FxPK{S)B}slGH9RDx8{&HmL8-#?D~rM%#R z=9gzNPnRE4OaL?wYDUJ3`@g?>*b+ynIL(k4-Mf{8!kqc(5NTQWcb@6t@o?JzK?L1v=e*ZJ~EXY3SZO%ULhPRvrbie6(_JZU-1GznwdpE5qH5b}m z2odRGDGB>G+pc*k?i1(Mdzt9_(Z=Q9Y42H3Ra|RZ4SgTaTB}^UYYzIH-^jDUA$H3R zQ|>U@xA-Gh;F;A;wxT+3Y+qR0ROr_e0wLK^C*ILqjk{d?FfrVS6{umIc%(>EkcY6Y z`eu7udB!S0SMF^>>a@aKDf8+?$|<`mrHK=Y#5h#P$ z)Lk=kh|MCqo={_#D=bBo>MbV@9o6V0W*s>XnBj6^XhB5ZlR6;eHs_S>9r2cJG6g8T zysJI)q-_8ih{l|^RR({bp0kenP^Nm6(diV_t)3G%0QV` zFF^ZFM{DYWM!%5-tn2bWppG$~#ZT6334~>Tt+};8GzLT(x|Qmqa@SVE3`E4OI)(yW zc`Q?qe6m8~V$Sxp)*+T5I>Mg(btP71)e)wNr1%{j4+Ti`&JWBat4(%Ht_{Li7lAPm zX3U=~D`i~|%#;xZe6Rpsuj<}!ZjSIlo1(z7d%7J`lb(BFTzaSdn=0KEds{crrI@6n z>LV;1jH2BJA)BUUy^1;Q3g?hz6YZa`}Lth z=*zz=I~N_nL%<;Qwg+hL&wHn9Qt*Os6+`p6xP$k3F)q?i{BY4tuh(tS3Gcbf2@ID1 z7HmLDHnWG;Pkrxi#QLnCXNa_H=1~1Xkt%d)B%NwWOGS_6H?@abJM%%b?SN>I@td^g zW$jW<_I<7?Q>}|5CzZ2v3tyeEPKVQOb`9|W{ru>9rQLJ$B>I&glwHjzYJ;LkHPL~`BoH>-_7u%s^{ndd5#m$#}% zSS#eQ1bCm-9k`m(Ra>C$;NDsVuL74hf(FK1ZC%vT2Fi7W&%ArkpNk%Mu8}yVf#v<) zvKik>{!}(+tu!XUJb@h+vT!UC*G(Mh)i;lxu_Z%A*X7; zbe#&3mlvZ-qoX|jwRiK)nUY`heAvic(-X|nwXK!3M9nEhOuvaS|Z1mRo;&-fnRTD%NHddPEjvmqw z6`8>&&2|r);vsiTk24*k=T;9hH@!D`#WWO{Mec^-N~XJCW}_)!INXE?Y`GW%>+m+R z19VBtljMrF> z@~YihO4r}YEb)=UsuozO|8<+Zqj7-kxQzF5Mbj1G+9(!m^DE84bp=|yVyZ=2ybHi* zfToNbGp!aeKJIg@XpGY(?^K)9H=!?{ekU>WlUIFPn;zRxp$1^yr0&C^C7RQEJyeQu zrtu!m&y($f64cj+ zpl_C!S|hvM+3*KpC#|b)^muLc#QsmSD1UUQYa3hj>@Xr|NZUBo^kt;z z8d0!Z44zbV=Zk3Hd&ZZN&pR}gG=G$(93I>k`9RlfY1nUHu_kx^4zfl+OG<6i`!*T3 zj)!gtN;%XKmzggGbh*%nx79{u^=DjasAm7<$w}V-h@*79P>y`l=r^Z=h__2`zc8$D zQta_b_n$PPt45l~Tqlj-WZN1cYEZG*Y>$c( z0zGx;$=1*sfLwX9v#H((3+YBQQQMrfk$--9|1Il|71?B-+{jY%)No$4MLqY3mFsl`uCm2Xz2(x90lf(y{(^0)wyZ_# zfKpl8(gEDsICZ>6vt}(z3VzbX)w_#wquT_Qg~${l12U+r_?QUf8ec^lENW=F=J18= zpg{vTaaFxP$P39h!L-zaFbIVM11JwN7iv>j)~>U;)vKuj|3V{I+?)lkh?@{;L4pFf|N+4 z^D&%vG?f-MM89Qh~;xw0+QV zX-G#aLHv(t`KADHA#mQBPPW(aq4Rn*tu3%=CQG29N8nRLqho2c zPkD{pZP{z^ z=y>iDQm?V{6>m#JGn#04I`O`o>eKrSv-nO+nkq-wNFvu)4UWSys)8v_fdcK1oYnLB zb!)-;%VLQAr)qfV|4NcUz?ly!U%uwN z>|{we%`v=!#zzH=e9D;BjbIRY`$#hNs%i%`(_ng9TRD=?Fva0@lJU||jpIHgAhT|w z^6I*B)LnfvNLS~J$nnC^#wGB^^X@#g%dp5lA2v=@(?-@uwiqshzH_~+$HRT`9P8B& zX8=L8kJ&!02l-Hbh7oPmW1CUPl%?!_-VJYri5_6usRjM7$3W-DGk+ z9I7vBE&rZGb`TvxI!`nd-@Ha@Whu&NMigO*|EH1*8*;@qgm3Ga8hoJAZ3SEzdLxtY zfLV_riD75-8nd3{x#(ue?rcS$77BkeHi-9gMgy}n;PZ#h=jpLhq){H93me-tism+6 zjBhgnh(&RCFlD}w`VY_o^5qT`12Gf$rAloIExU(81`F@z(F&`fw6_@(Ld6VPpU;(~ zSFo|4MCohM1in$qVHy`1WsyXFVbY?BR2;>bd}GKF<$bEnMiD7-gnNM=K0~e~w@3Z| zK>j45Pl2QXRYdVamjDmqq9UgIbEW|Ny@z>CsS%t$%ZaYk(7#Mbz9Li~T8Zd_8Cp$T zAG`3}lC8PW1`EZ!;e>Vf+b+>|!{EaZ?k}RTCsq`P zx61Id&nw#gd8czHS$k4=g&tAex7Sl*?NN{M9Ee|gEn`bOiq#A&3p3tr#fb@>0n#Rq7BrA?Ef zhW16?-@Kb7Z@cDBmVo&hl7`v&_k=SR&P6+i9MzML(Kzgy!UN~BU>W#$Bkor!eLHcd0jS$ak48zY+e_NIui5W0@vcw} z<O#p={d!@bysB~O;HsIqS3i$`_K1ki(G z0Tqw$qL7oDgVu(JR-N-by!F8y7jK^ZjD|X-{gPt5#Kc&;26_y+$(^vZA6aa?YVQ}O zr@x4b7|r~~xuB1Cky~>=N!1E7($PYsexJ(S1e!Xp^eh;DpEGQ7-nQ0h5&lhrfLuUM zO#+HcEo#@y49o0ypSS>tPu33t7lL3tu;g-tgiz%}6?Jvk9`^-qGW{TPDl=_XszWy% zRWcEUUZ{RMDqM()saWXkYTtr=b#8G1`rRHi4=&~jW3MpNI4 zIM_PEjr(kM&*n!5gBIXnP2#t1Iwajs^!k5xpUdh?^Dn zVw+|60*mU{n0XeGZJy>nm1RgfM1wHDT_sMP;dVZQkoM zE5<%DnXKFzj*e-a!3+E2o0sYCTm|k)Jow%bgvMym@W@nF0V`07Iy*b5I%CWBDb*4_z@j!kR5-_jR5W0jOO))bouvo0k=7DKDreW3a8tw3 z63LVt3Def=+tJb?{x`xjhA!^EYBKl3*K6Z-(v58^z$(DS**jY*g$=iT!-}^y0wEwY z$CBIObj5hWLa1gb)BD2rqfm~sQ`oOi(|tvg^;PZj(RQi(2-1$!ZBzGC)j1S<%4gpYvll%klhciX8TAC{|rpP;U&te(-o~}9e zh6(K}CS=n6!TL=LpUFNWxcXl6LXYV7)zg)J&&>_cFcOpO@x$bqKZwnbwU7;Cw37K$xYcU& zc@wg$8Jo$A?7ay2^{&k2=zZAeHZUi<(SekV&!<7b?`l(waEK#VgLeCmn5A0%Gz(Km zpOK)OW(Z0*pTwx)A)5(hb^kZ@K3?j4#x&pgAW_jRqHUB0OLJ|T2RUmkDQ=Qy-GE+~tXZtps*M@%2pwYuzv(UawbPDS zhQ>cZ41nnt6iFOFW94;*l;l>PtFB9UVjd8L-$E0L;N6?72C9O@W0Pai_89De{KMm_ zXL<`4&Q421Av~sUp2^207;05$>uYfyr4jMzyijB&<>GrY&E8b&=61ln_1VpF6HRwg zJ<*3e*2Aii^Hn$VPCf;u4xI~zy+S@H(x`q>b<2~MU|x?wyQhY2dj;l0xupHcZCOlh z4eo)YMCu?UHL6y54;wWYC2m^ zp)Hy2SuolCP}OK7Glf-jwagiQY-Wz(p80Edudif6FwfaGoiH4vJb_9>E?<;ej@WN6 z)}Om9{WX>#gEe`7iRe}4b`9BK=9&2@QI04M>W=NsTVU-|*j6+QtMHu0Ibq&Z>TUe! zTJL*(Y)refc5q`p{RHo6RISs3zJ62#kwZ~THoFwFa?*h)LrXSNB!f}Lg%@;6EN(%olA;>07F?*qRFtI&%$YC z?P_geSUYC+bvp%W^P>^6JRJVB1DjE0S*<`%Zy?98_PhMd}w#Cg2}=c*pd z`)6$rDk(L`UJY4MR{w^z1`ZM;+b0OpFMi~zG>u&cHJ7Z-rwKGAjvCQlj1XrE+(O2Q zsnVQBD-1FD-O(=@s(0}_Vo2$*}O*%jeu#Amx&=&y%bc&tv?BSv?Rc-s|U zGqI=haONo+FB5SNR_JT&?y#P`qizwmF0WuvBIM*YTHQP1{FRpn3u{q#G%}%YJLvN< z*5lm$uTLzQZs7Z}_RdGH<6n+IL-ZlJuGfp|zh(wARTvifN*Z2lLd{Q7ud?UZ1kHcua&ELz~>LhMyV1>R7d&2Jq4 zrG&Q!sb?YtP@5ZfEmF62XNz%Cs2kJ}>0Q+A(xdOr?`d9a$y6U{Y}M4)rk82L(H~wo z5Wc_;V#XTEAj;@-iubO?stTtxVvIQiXm?ex?646BK|cRA9o^8v{v5eLtwrjAX^B|^ zxM?5U05TH>&3dYZZV~|!dVgk+%h59v{v+R{a4QRcHHq=+pt~iNQCV*I+CeVtUMWCM z^v0o4=!9jYjnf+ufd993-R7=+&{MP=fAJX}WKV7yt1`EsV4-CZSpD_u*Em>bR8c+N z7KYqUp=&vWWH_4-4viMRgzo6d1oU9XlRua*~2*l9t`{I z3X=z7*c&x_rZyVSrM|N=sr^#u+*N^bm!mtc{47ZtO%YtoQ9|=OXb+clMGot8}v zwWW5wnBs@lwsQhTBrkMmo+q|q?E7o{c&OMA!(*HSuBb~h%XCgRE|mSNI!DFt1Z<_Q z=13lXLM_!Wd1#%SdpEV<{cCVRyL>T7f1ETxmtw_ZWLmr>Hi$CQYG}7XJ&=pa35Dzt}2E$z}m=`bTUHGy?0!RPnC+O)~A7 z+9ktgB3fia^=)teoW7yzaR$ri#8nh2_#I9p?pRece-fyDB> zm!rbEOEEYkNmwv(#bKkg3>tFG=9I<6B?Or~a(arG6daYQ*ekZFeB%U8OhCU}3CW0R1U;6ZmUCZ6w2{zB08{j#l3x{}DYuM9B z!lL^qjW{sl!o9bdpMG!1H1w`~&0GGufX-2o4trbZUc9Ge!(P3U6?AWFKcm=3z(%5S zov#n9S@LnN_e?1RvTgW~M=C9(;kIAScceQCb0k%DR0)|O3%1A z>-~RD2tA$bNEzem7m>@^$1cc~QG$(1Y%;%;Y0%%OqjNsN5Uv_Sl`rG$wCE#l^v;s> zTzSR*8gtZ*a@AHI^HjrIn+wY6YM@a8HNF-?YvErn2O_{Dy%otbJ_=il?bKK6UFx8|C79(_pdx5esJ-h1{S z`>ow_m+!6Gk|_hZb1Ff&0Mkz#|H_PoxENp{?pS;D#oU`+nl0FAd|FjyBf53&M)9T_ zl0P0Szid2b3oRSh)BRTflkNnooKA3xrPtp&?(PwBsu^Z(tZLb54u&#GQrTbpSMSQx zFj}uH2`Yc9`EkVoNJPn@;A@|;wk>h9b_G%>tDWQsG*(MroNx?WOnU9B;S@LoRH)6< z-nzii-_V}z?+Aekp+r#WT#KN~t5_Aop{ov4_ZjK?pG64ywuf%1%etbw*X`FvAGu`Y zdh~OZpiHA^YR_~GCHsDOj5~RtovAUn9!nC^h!pKmGB}x$g zas6|)kI{Gxe=2l3>RJF#9uS|$9r8iEPtaAy@6?-ARB1!-OpGLgVTxELwdG=38ryGe z8>RWU$krL;mLGaFLb3-B91DWy1~AVjQlJSg$SEPbxxR}sHn;7zUR1g=TnQN=A(#t5C}j~!$AsT!@q?S^h_#C(ew!)KR& zYr|{Y531d2-toeH4{|gZJ2nWrly26~LAn`fg9ya$6hzKal+smZkmpvnk`g~k`>Qq!^me0kxxzNYB&5g*ti!6+HyCRJg$Q+!l`NnQxsZiJz9POmdQm##%1JtWMfolqP&skssyP zgOv-+3=FjRGS=#RvFXF_0OiXoH1hh%l5ze?n|Xy zrL6(ptx#`t$|Q8!Npyot)9?seEHYabboD7Tc5RLmG2Hz^`jbJxhGuicA6-`nukbyz zfp3hxYs+Q0Auxc7>nc_te$q5AAK2oV{B*fA|2?((B9)M8)=*O@UmchdViaZ+3RAr# zh~)Qy+4XUTKRa!SYD~@}AdhSqHg&-`o@zl$l>*U_zeUJu?yW-UOt5t zuzbdzu{4e&;n$zg=(J%QFm4cLJZ)$>5?*j#)wiyZfQ?scbTlGZ^SFeI>hU4AM80cU z)h^rw{%e`*)P5A6ZEaRhGT zEjr6bHC5W^y1-ydySu+~|MDeR(vI3k{iDz32d4UbyP3S)h`Jd;a}sZWQiOm@Csd>ae6% z*aW(5PMVL9V3XxcEo6+nHQzCW+zNbxdVNAeX!rUCgwZ=Y6hY;IS-iT=z%y2t=MjN@ z(D!z6B~=9pul(4pZz~Iiyd`#tkW`;EIH=DYtl#Zh{?0lPsTLBe3jSW}?^3;+r`OOa zzua>uA;?mcY|1{THC(u=Rr?+J-IF+3F*BY@q1nXV(S9lzR;VlEA_b$Ku`Y-K4vvmz zKjqkY%KZw?X!tu`Qr9!cck6e_)=cD&2FTrcM!eLRxG#B_;hV?Otq8|5BQCya8f|+P zDcBDLhto-XOa;$s$y7QZ(7V+(w zH1C+?T$1o#*fW0V*QZ!}1J$Qe;uOa(=@X3qS+!~6y(BsCG)ve&VbIo|Sq~Dc=Gr^^ zWJwo=L^(~ug{hmR@Qp2^#R+d!2u*vHgxQ|b6LJYtcuV>zrUI zCi1bd_FJD*I(^NfJA|XXwRBn$9e?Nge_XxgUsR3vhC6_O!b6FG(kdm5bc2ADbPbIl z5<~aUNGjbW-7qvmr*!uKLw5`fL&ur#`J6Yu^Dpcdd+oLMeP5Rtsg5a6$&IRdHPVV+ z=RR?fP~FW(b&z*+s3Kj}aiF4{O8XK{5lqk3#Q~(?s6o~BoR!yIhJWK(7+};Wqk(lT zGAw^^3Df++no9H1%~1!wRA2B|LMuc{?JfD=o)8|z9*fn?X*R1c9`k2F99U1HQt|EBgr*VmlikW~ z-S+_=vXlVIJuh`uY`ZGz0pShO24UzZMV4&0h>O_Gnp9yZbd=oX3xTD0uMo?Z`j32H zftz?^BIAgU{ea3MqvwaKVJO;Ct1Wv_dMNnfGsnfb_@{@k3*Ra*4FTmvo|}uuKV5!v zVnHIS+61Q3q|#za76JZ=eH#_-ck!CWRQEv49ps~{Yri!-HD$8mJc8kWm_cilRJSbF zszg6UJ-rjPvFZP(v!n-J{s&2H&_cQxOQ&NlnLzn~7!_hKHyl16u);jIf!$3{8w&cJ zN_HCmbi0wC^+{F@)J3gm9*DIPrxsYX?z5tLz&KCh&ofHOc+BhDt) z(!fY*?8?RqlOPgcUb6;r3O~`gw)96KWicYbVwPDqOSc0J0RSh?L>yU^i?fP@#tXvO zTMV^mDI^&n9cUKYHBjh;TSX@ci>86g8T@LVUR0x;vMZ-*-eAm>P*q^PJeCnBQ>?LF8Ra14o z^qo?ZcdSL8c5BCrOw-5*Va5h_zpO4;AU&OwJI&|}kN~0`yH04sSlVemB z`?^6FX0tBza~V|9BuZ}%F0#E8P)$b(ywUYbZb&`kTqyZzUL@>h%cfLn+MG;5l_&%& z%D6IFtpU$)8j|Z%0Y>Hx#y{61+tWr1p-_l+*`^6<`AbD2{cFskTFs!7m#I zos3^C?m`Ur|7p`ZEhdf}sekBDtUlxmwq5#g`)>QZf$6Oc=!bwgO=(%e*u1kSZ^h;pREI&1!pR#kgOE=_KPldn?sRGaM{pTr4!&B zn&$^$j7$HR5*wK_Z?(xUUvs>_1eodtcz^A3`5ODfsM=-npmtX_4=2vCeCWUi?{kah;O;?ua&JTo~V?HMnHe9 zLeOWFWqmA;uydEzI6oiwB3s8r&4W0$X4ZV80fbTtGE6Dl#}8q}4F$)KkrRB9K6;ET zT@Z#?ofI`Yb=4qyA+`U#SVB9?4fylnsYZTQer8227B$LJU14Ce@6+PhmM&jn=TrI~ zU)`d^be?{po6+C$z2R+d&i{=lJ2zZaHL*49LYfEjp}&a7-|G$8{6nCto4%n?8O>bH zkbeoUazdbrfmfdz`YIpDv!=?vzF86|JdH7q&8Z6X|6L97M&y#Wvlsv7<+`=w)TNj^ zP4nj~e>Z&!=dv~8WnJYp8>&z&c5(f(@BTGWFHvkJFa`v|_XICLL;+y#dA>v?G5ue-T=2 zhkt>tDE1Qm>5Dx85856IQAmg`{f{cnPZ~qc!!JRZ#-&L~1njVqBFU?u>(aBen5=Un}iq{_J9#(DbSzgO6I~iWLZwW3pGqJgd#`bYJ zM9soUC{FPjv<$4?VXu({SonK)virjhX3LfZxbX9Ho)?Hmezm?;<)Yr|VoOF|RZZow z_QfM2s5X@a=M0=9DO85C@%u)@lZKbjs<_7T8O0qUh1yoXXKGR2(Hc=7d%-+288I&+ zK_ee4J{sw6nT@?SV8pwfpXQ(G6}&DceotWTMAeqMNxgP4)Z>}hUNqij5oQtCH0X>u zvYCecSM>Dp(n4%BQTE9~5_KEx{y%;LRoVy}5N#1%dF zgn1pA@8})G(4R#GugV`PO0Ymx2z*WqMmZt$Ng_keC-Cu zE=M;*Gg@|E33ptJ*{r_I4Oj`y_X&0BFa!2OcLTBxPN~Z_tG2~`rLPxlC05SNDF4=d z7G_^|?{TS$4|IEc3&1nAm^+yX6ncqV1epWPLmO{S(R8p(j#D17_pURrP5C|<=h#0F z;BfJpSoUWJ%3d`(87@|dJPgw69g4+dmUX|Txo^jaVZ;xBQBPdUd0&QUxzDqsUt*b@ zpRNa1tm1!f_V}}i`f{Oa8operJej|pTxK-zYxzpmZtT8bi(if968rhvvstm}96ps~ z=<~`$%BnAz&p*9kG}z&S)81&u+~}z&h{k0lTKL4+sm-rs^q-BKIZA6V+6dQVHF&>HQm?QWSm z_2nJbb)3X@9CJjTy6ko_bUOcaM*W>!htko8ay*rC6^@P0PeT`N02$JQa~wlouB^HH z)xPd^xq6jTbsP&i(X$3Kg9NimO#$1G{++tH!fYwD4OZ=xb}&QE!0W1rvHzy*9QKSz z(mT)*N~^hiF>Zp_&JH@&I&7S$fe5D@701{5wBIsWJ(F2!IeesUeBCg_22}t8t|)0` z{(9LtPC;M!?*@o;(t{p|V)E3pG)oqAN~SfM7M(dOm+A#qdg3OJw=FU-fgu29b485` z=J>%+4NMuoMoT{i2UYVX+h%P*C8h6YObx+m{gk1ze`iM}X$pG^8}7W3QcCCA0obC&xu` zu*c1IDP&)LVzColv`N#xL zkB!z7E|h3`!|y7Ja@(B$z@BgAhRU6j!x<84-GK}V>U=i$mat1UCSsQV{4=S{pt5fk zgW48N8~dXY4FP|)ER9O4|4tDLZhuMQkNG?}?=`Zb!T22eo}$XzOjpLo&_eX>l@jus6fQlyktocKpxeN*n$?<(Z?@#crKhlpl{R~^Ro2mk(asnk);$>^a+l$hd zdc(CPg`I`X^16}~-D@EU&JFY_GCu}}-bFEstLa$UemTP{Ty>DIp5?-iiAX3Tl%PWr=!EYyNme@x%1cXl1`ST z(i%NAb0~hnFEe@X;Je~^!eaN)cMptWrNSMzNZC#}iUu6B)s^40Yt;O#pR$YgvJ>OJ z$*$hWbLs=N^!Yh}4)6*<{`3|75&(V}?a7VGe)AxTncx9alAwb$1Ly%b=bKl*6UqES z1LPa6&KuqeNH=X2;6wWSMLWq^n9$l|d?dEU)6*Y;s|77yUtn01EW+&V}6PJy>_^|1#|9`Mb zjL!AAVLdPY6_32(al!q!+)IW;eRvH9eZQ;CSl^i~IiWR42>9ycV66Riq@!}ioRIbH zO9pofn&6qp`5tUFymbz~m0sAxPuW@u?94Cnt%xOMlG7X48?POZA{e6r)YfG>j2U#d zk;(N7et9<{vqPEWyN8~CX+nLmg7DhO#qK}@10&H9RXv+a7~TecFlVeJ$Y1fJPb#zA zS!X++&o@29UZWxaf+X+?R?z*)i;ffu%;d<6rtL=v9@CZtd6nIG#@%qOuOhDR zuJ>cb{!==G1*;(h#YDP)pZ{NC)G_q=a5^^h3gJ5(=$elIdSqiA4OnY>wMdjh@t1~8 zmGI?Wg+7UPh?GfZb^NtMC_RUoliJSuCN{RVWB>I&wXlRZEK%6u+MT5J0qNPi4_$kQ zdkI2yMj02RhM(rhEYHA;b-Vr8JS~sJ+RxWYMR`IV{z5NF9W}3M1oF+UC&M$0!!FUAatft)$&o@-HQ(R7p(rHt{+L0{4oU^D;i@+R6c^Jl6u z&Z>5c`A<`rr72y{sLVkNgi6XI*~ZfTATR!01>moxeX?^#{Hty^goy<;g$f`3a8}Rw zsGyq%9X-QrgmUSdgJy!02%pnA z2PGxtjD+?K6`?Nl7~Z`w>2ShC(h`eiWkC2#Ky4aFSscr6z}rB}JjT4JpDbx5>-hT4 z+U6)0-~v#4I`ZA_MmjY|DXFc%uv8EqzcNf;MMY2)5D#4Dt<|4VuvOz0%u7O2O#Wm9 z)!Xx-G{3WuI&4rwwUNQtrQ4K7tw2?h^Q1ANu@2n_c zYa%F4?O6V;|FNR3yQ}4A*MaO`-WB}WVSd4??N_e6hho}+W9pn3gcq;|ZYqarS6G0) zCVMJ71LkmGFm*o=54}GPxCkwrJ^H3^tW;urRH9*>?t*Q4)KicSMMq1Avf2$YKt?TW zv36W>sF09IAUS@}gDsgs59Zryo{9)lXIcpkV%PyiBRh&4YOSr@yQ9e_z73ztUFNG4 zz_#WihrtR*bCM!SoL+AbaU~;9fkgz0y#}Uw!IyR9B(NTkK)7Hwm6~q=SVX+n!{}Dp zsMke{1Z2@Bwz)>}kKFskEP(QZdAbfgg3JIE0Pf^sy}+V{A2cB9dUfse#5ISMD6T_r zv=-B2vYI;6ymixA7XC#rLk+dZ*$Z&uaTr+6)1&h8c*~pKms}fcPYbV#(fL(n@7uP_ zELnSwCh#8C*3YMmEnP}#F)$`t@$a^a?nP@eE!|$S z!CkL#P9I-*=;sx%*#BHo8aF6u@*9Y+*cz8R7-yO^SFV`M#6+sXLarF*k5}y=b0#;f zy9q{-Y{HrSIp8P-#~XW=w+JS}eP+s3&Ch&!-@Mb+&vduru9U09dN7mx{0D+R9E)m) z6&<$4^2oE0DYMXwezLHtab&%OD8(KEb}&m7Zmkufc@y51uz-A$C>q>S@_oSZzdk?J z)I5d6UrH;T#s2!2{+V6D&V$E3PRoO}VBm&!!`3D@yK(%W`m={l6M$q1x2N1tP3FV< z;19l-Qp7k|wlx2->_szi#;RH_4W$mWAg|Fk&4a(9@Fz`S^&nH6@^IiX(e(SD%`?31 zLOBDfUFGuR3n}iPP5Mv;JD=8X6L6YAOVh_RqTSN;xxGk7JY$-<3F!Ms-KQK^ zM_WA_*uYM4$Q*Xv?H!TQ5@*F3lmdE}F$bDmtegwJVtq?Qxbk{r*X7w33f5^4jj2wsc$2RS_KIp2kFZKt$e;;y|a#-YVXK-&@V z$LTa{6Jb4R40WZt2Iv69E4Y#xhieSTs|bqwff%b*dl)a#H;cOin@7l^-iiAvf=vkK zcXcNnBb(4;^2BIARK$4qUL=zz9T)DS~KvsoP zHkxXMQS`>JTb#(&d>mFeAFcj17AT8vuCmV=*zlh{ZLB6mR1rcoi;|xebGxq}2f9S%mPN6BHzX1j-CuI( zE4n&lMV$!CdE>huRcwkw@7=2Iv!T~v)bsaBBozh_MZ23i6z?J(zv8G*^zGN86NDEA z`d)?bbW67v)!iLC>iykwQ(b1?p?Io9wd|a-ef#Yi`x_Z(hI)UUSe)-&XWb(6Hao2ague6Q~w?3%65)Zpk8z2x4qH$i~^*uFgy;Qe=eg*ti z7b&yhEOinn{Q0>+`$NuQjLN8-UgQtS%C^fyy_=egx|@h#&&NbR8>{KkLIwPqH*qre zdl8`0rsb|0(_)mKXG(W}`(J{gyIn%;@8a|Q2xiPO7818fQ`~p=6Jz+S833$cZ{yp4 z5PcffjIx8NaN~l4qDs|I6BDqhQT7^JE;!8QT6=bLy0jNU-J%`osujL@1$XX*WbB7q zwqaNiNEmq@5Dg2yPz}UP!w?IO0?w6d*_CNo7ROeGxnA8#bFl5qfOvVAQ#IKWG_2|J z()Alk$Vg;q7u|c!4dfp_cE&hSF4j zR?eonImQYbX!yn$1=abKel@k3xICB#;z%XVqV9dToh zU9psCFm{)>1-Twd48bAsA}tL>UW*j>i=oE1Wdo!Z`)xN{>))S-J?)|dY+hIg%*o{V zSi}M!lgmCCGO=htm~!COnLObOk?b6uK$OJP{O( zm-YO&$fyRD;*M>fv{tZoe1rR&h*2h;g_5WGMXe+KXWQk{FZK!rgH(TXe!3p@#prVr z42!r7EqM9UzTIX;+-WW8x$Zj*>ms%f-;Fbp*W1I9_3AlEf#xs3VOX!+)YMP`EeRto zWA*B@;*FgAxOGU}!n~uGVuNCez6tHoQX*itTQ`G+c^LjJM z?Qe1YyWn5)AeDc*o53Hx2Q&P_iNNF)JD8j2yf1zr{)G9U%P7f$GM%YT9N<7khy0|z zJW;Tn^cClRRHF~E`Fr#idK#A}gE_}&XoCOY$mqIW3GUGS)x6tE=BpHW^Y{1zL?_Tk4 zWA{nk-TP_tD)zzeXojT#^hBm&#{8(`cyWVjglp2vprbYhbpV@rFO zpeue{A`76FAYa3w#k@h+JbS9BX(yl5M3VsupcxW&{zr(FjlqMybJ{?rDlG`)L(Mr+ z0Db21UU&sSto@x__wCXXm^DYKh?$!1;%@sn_yO`+H0Eya9yP=)TihcrSGc^6x$MRc zhWnDZHpy?_a%VFEqS|*GP#6oebLPZ9uu9_-f6~ofp9&1kcierLCjB1Z&PYepy${a> z%VV>FcvJBmB{#OevA;y;o4ExqU$)pj8$?O&H@c@@d>D`Vt^?HKXLYgX4*I z2k4m@q#g)`zMpGz0(j>aiR`?)Em@pKAq4SGQ3ptgHoqkqfKR8~UHtB^_G^<&#!KOG ztP8TUD5@E+6_xS74#kZ@{D$Q98Qh*bak?N zGIY5%IlhQbwTzt<=ltI12D^C&g6U~~5sI%T+IXEmyOP|GgsciHr9Y2eZa+|DO>Za~ zTW36?KX&~JM}{1RUa}4RT^7lvvE*}1TzSe}o%mJ6I`J#HRWFaGanWw6WE^5xoZK;B z6anK<9QQ7a|44W z+AhNOhi|W;N4y-c6XR#1b)|1x`c+%Y&zW<>%3cNSr&Y*apRCD5KZoBdwfpuix8M#7 zpKguT>E#4&cu8^KJA=+PU`i*~wl!O{<#U*#WoB>0z+<9m$aW zZSgU$>)Ur8X?fv{7#<_8zn{SWyBG>P+rm`DOXnV8)5tLnYQcAsH`sS;S{xIp_K5v- zuW}ID@BZVt*v)%NLf5>%z935?i(cJ-p^2o_Vofl*l~5ipy9pxxDe){}{W9sEi_RQf9d+dx!~b%7ug&t$?b$o7O?%eC$$-u zwK#CYn9DNDGY#S^H(9Tqrt#duhi;FUw{5a&FQz(45?y!Fq-EJOXJ|j$)c&~tTQF)_ zI_UQ7uVfXmvV13p{+oWeV&@}c;`BJI!Eh+X5z$asgkFjmZ z4Tc4KQ>wI$r>8c>mXwxCjfPz0PSjayd%HvcOkHf`=7^3oWQOxH6_7(HdHPF#IX`wj zC_OU+y+&(!gA_Sb%fQW`aiDc)$NIYpw-KRTE=Ft-0Q~EC+|Py(hjo?BV!@p3e1vKB zstXm`A?jQw+04gNBScFv0jZeToJV7>SjX%8zc4x=gFyED#NncZvBCrv*TjZfz|8QR z4Z%RIn1wjcf!w^G5w z+29v{j)xd8Urapt#$s@2Ijj23-k3KR0lO!OAT{VQTsjL+jYBGF-D*k>$}Q&Sxa1ew zKu{?_T`3N-Lly*r<%kB@COFJbgT{P#i?1gbkn2RO+k4a&hf}odg@K|Kxfyas#B>yK zN^*X1qqZI-D+Y-e#M7{df>)IfgxLl|-&W#Ov33c6#KJv5YFi#+>8A0n&}#h3W+ zz>co)#9VhhL2l?G&%KxfEjMM|xi~IO6 zd22pF&L)E%+9PVSFH>&Z#J4T7aJAt*MelmY=gi2>Ej z&NV(uvtZ8XTqGiqtR1#8nQXm`N3kTH8&N@}Vd=aiDYu&T>jQ#0#zZ}hDmgGL`0>~c(hxL@1BxD#HzYi++QP}yfOe){JZ04n+r zjiurou#|U#VY##8Q#UfIsAocOioH%wh(56?`M&eToM;*Uxf2ajPv$*(ekNzz2ZPrIcSb)h=c2 zE+th{wB26Nlk@#vb(pyuAm?dte*~U+ zRgvFLlDt?{fEs}7!^G?PU%Y2~&b}uO_^0PjT*MQY|6Q0+TRFD$eu+lppLNn~VmqK_ z<-f*@bexzz-~~nanFTwofmvn@_GurNkjGl2Q-IapFz<0}mSDFJ>n*@{M#jj6UeuiX zx;U!|Q;v@6;x$4A9?-rQg1?o=s$wyvF4q4*eYx}b&UxfPhM<$_@mmM?vxhPv!3vk3 zXz{@-&bv=4_oD7uUMi1mMSE5%kD@-?QR9NB-(=xGy_h-27isft03XJ4k2MW#(L8Jj zM5VXFx^@z;FB+tT z`m)balQC*FC))Uwr;X{7S9H&0h2L;3D$jVeblTXXNz8lKFzF`Cwfll}@7h=}H+tjx zo<_KC!<}qz(63Ifjl)-}`GOdJS&Hc?vz31L((rNnQ`;oN>LN?l^xUD#cvKm3tJbJs zQT$PKjx=;r8Aye_pSoG}Lci_k?E8w*QGN5ZpL^SrX;&iigj`sO)(x_pW9nD0q)+0y zqoD7>6vhRmtcYupK*wX8?f=;hMbx(bUfd8t<&dUYXJ;|+)LhToIG-Nn;&_!(Gn$MH zX@y58E!^=gq-8L>LA5%E$GX)qcJ4h|qjzu;N1KG=n0{%ZB8S@=t3AzgqvFqQ!Nhoa zt!eW_4c&5J&9`AP_E{N4_NifxM$Kh8gCn`2rgOf3B(ooZO-QT&I(3Z?VUj~SljgY3 zKxn5n^p`NtyAG}L0cDcD`{?{$pSs9IJy3G3I-NQ8sPwCQG5KnR=MY`^HmnmmTV9q_jwfN#YYmB~PYO7(fxJj10JXc~B0ra(qJipIsA6??NgNnTKka`S{88EDT{0mg6s%MsY3 zxY#4)gF>(0lcz3fjxT)%x>o`c4h0$pzmni`eyG;YKyfPg{PkWW7SEQSKvqGC>6#z2 zzuuB+mGPIsKkqN0LYk#$*IogpPuK3RNvNJ+OlXtOYuv{ECl$5BLFk@xo>Z-hRf3V9i+i+e8 zX?vW4;7*`B^gcEi7F*WaIu`@AYwdi1%q$t-N^JXIoEPudiYRE?H6O9=9yC#vn%k>? z`u>>amF1k3S!$~>MWgecs-bKI0Ic;kd2i z#J93g!OUmuP~FS+*Oi*3r1Ts{hMBI?8=qa7aw0$mf-Rfji7ris^MwSDM4a=DSF4-Z zcDUrCFwp`_vj@DohREZTmCHHb$5AaJEwATn(-R+Nq`j7lce;1CKGb<`ZYKRP|MN)n z*geneO^ltltbtC4ndY2Po1~;)CzLUMh$V})#Y7OrX1Xglgg7}@=i)FFc+8f^>(a`7 z&EA3)E6RNP>FN(`I#8faSLBZ0caI_MG&)ATj7 z{#8Y}B3b{wYwQm}u=`^M@PFoe=KjROp{B`@<``>niyfxPl>LLw(lv<9&>+=Auf(HE z7hPRvC<}V6C~sw~D7Z>W^1%N|+_Cm^o^T@hirpq$Rp4*5OX#-4LFYldV0l8K*O%V{$x z7sSuPPdc*$vY$yLo0ok!r$4t{qI>Rhyq&{5yh}kxnAT@aoFaW~f$f%7 zibMEhpg)&`V7j`yf5of*6B=K+x5#o0A!QTkmnnGYOBT29kQ6`a!LW{I>@0eoL$AuU z@h9^d6J-kWSVOB?3lMz4B&laY{g3N72)Kdv>!s&<7f&|zE&%Ts!vH}2F#6&bKm_o$ zQ^X&`|0RMEK&VOpd?9jX^6C~qm#P2ZE+=}9`rs1YOP#uCMDTMGzapojh-I!#)OMG; z-=D3WcR;GCF4j57_dUV2Kf3|OR7~_k9nG4&P}F2Hj|4fq({|z*yn^N?a5ejTjgNvAPkT1-`$b3IxWt9 zFA??1{ZCQpoL}=T+Jsnd8bdvjyd;2qi!Jy}m$cN*7@d91;7d%xKTZGUF?Rgj_9Uq= zOk7bH_-)Fzf&L|vF^8;GEo$i>E2>EsxmBM5&X>aGF`+^!ek*A{FSEy3hA}+0Fo1EP zt(oSZHf1RY&mHmR`+=s0{T@?Umt4-MhF0U)yu)a1)K+u);<(4b$9^N8#Y*4(3x=#& zo%YKTM!t~?bgjc>1gWa?VoCFS4OsP6xQP8Gc{n%vi?anRN+Qudg{nNavzRJ zxXWJo$e$&%PYBkw933{gYz2Kfj~RR%V%5!du3X7E@pY~>I*;H-7@yR7Gai55CfLh7 zxPY#WKSfh}-WVZ`?tf(PU%9hS1O?h}iQhcNSLDlHW|Md|P*HoGvY=dj7M5GXQ*8u3 zMt7G;&%x9a)ybjRSmCS&09>LSUq?qZ!gL`zQ)NirR|7Cle8_iT@oQUv?Xy@{S< zW%YYEZP)wl4<}Y#G)UIO+1?n+`zU66V1Bs5>TICPS+y7CT94ATSb~u60ngEy33Yh@ zH}$=yLAc*hd0O+XzS}v9DV4L-0IDYayFW*8^pr^qOAod6RV_fScS*VIwVJOy!~XA| zK*m3SiyJk0K!7Q0k@lax+E4L8dZ`hGudR^Ny21SRFqWhKf(Fw6p5Y?|;=Xjv(Mi3- zhj}O78P0c2%@4UOb*CdT%?^_|0RBSbdpRkD-hDsOBo1Yco5=88Kq#%2|@Jkn`0${b15i`$Wkas5?4?Pv(%Dy883B zp;W6+9byaCR}QQAQ>S5QkvgY@#5%4mk;mR+aIRIRgw%q{rB$SxU9YEWQ3T0Y2Jv#c zY7Urh*$f(37yH6`7S%^+J^=1y1cB`y#T)uo2VI{aRE=?NY_=V#+C_%WYp>=s8;p#d z%JwZE<63mJ;{RZLhbUV3#Ac`$aXPr$YB!Vyq_AJgv-wOZ@jHi;3nDNKv=t4N_`QIqbw0@vLWF1T_y;h&*D3);GB>TfbPfJXS5T zdNi0XR5$&){bJK0{(N7uZj}<$yIq*!nua@}mZrTr)L9PI#oSYBcALR{ahBppSd*6F zMj8wqfkZym{cO>nu~!lTwWc1k?>6hbB;hr?ZD?>?n8*LHZFgid{mogS;78vSpJ8W| zCUc(ND14#T5mYw|a+3jI{t^P5pZ`w!Gl(`)246xuo`F;XYpZqOr4UhJdM~5%)JB|z zAoQnK=F{)YLAKimg|cl3f1_07`N4FBvBBz_>Kc$BuIO5R?YFwSurvkDeeY(ZFV$k+tL&@Rv7J`C zaEY{s!pH7Hsrzng`^Tz6RGz)e?(MYk!=P*P0Y{($76pz8}> zBi6^)vGwtqHT$f1@g=Pkc|SfM8T^?3T{Cr6A=fjc(8rdA)L~ZB8oHDVt{EbXgk36Q zepCp_)An6*QEBoQnhEx@T{;*KQVPvRruwPtuJR2#$A8}BXA!K?sLrv)iN1XE?udCk zy~c%G;ZEpJq$UXk)U$8c&QQcZ)0yI`pM-$+6+OBYqUCRRAqBFCjC$ss= zQzuS6v-s>ULDP3cc(&xT&8`%6zMEJXUQb|rWsyk}>Msk_6C0FkfJ;e~G>Ms(h!B0x zKV}TWkUINx?Zw(J=s7@z@}dFn^aTVE0U+^bYUD(h0pR(+eF{0hj_(M3Q0l1(M^J~I z`4jjDIib<`6B4-O5ZFqJS1M(;XO2aaN+cz(fUvh6qdWj1JawV%YvhDcZOJqqeGMSHmUPi2E>X6M5W)t{b>|Lq7q9d>xRB1|xW}n%W6mhwn^6;Eu zq)xc#`z^Y=hxFLkmSl=gy4e0Q>rbGtE~xFh|TVs;Wn!Bf^Pzv~^w$;gbh^ z{?xRD{=1T22>$cjej>YZH}G8RG&)+oCuTYHQpiFs>NP$39$~*BDs=0(YzjQl@y$_c zzLC0v-#_(`U(tzfx@VQuj`@~k`t*Hn+bihEoi@&#a=(7eGv)A&GJ14Rvbx?aZ{1|C zLM6JME@BTUkUNT5B^Hl;=xwK%iKqCpP7I0Jsw$Z6j|MI)X|vpNgIC1usY z+*Bz0Pq8oS(g=cC6ur0T@Qsx21$AZ+xIZc{jB3RGnT7xV#5gmVoSt$6K)pAGj)|Kx zT6vfxf$v;D^YZFa4D;tK3fUf6HXMFjs0>fynB0)rJ@{KY?sBZNCB6xnhW=PEy*7)X zNmnFgb9J!q#U$JRRlss&<`B!?zW18Vs8No?=S=bPf1BGd>0PwRk!Q%NC*Sqp{_h zjP$y5IDR{tW0mE{33SB2*ostmq4f{#@;zJYe$=(oH(qbh5N0<%>k{4^tjo)7h)o=; z?KvgS$om*pXX>;2B%HdCoBH6!sIgGaX!wg!sZ!p8YJS+pb*|`Ke}+R@xQsuy5|)NJ zdmy7#im5dOd)`j7?v)IhiHnrvU2t{im+Xz_9G4UX=!>417!?I9+79d9xk79t=mJkZzqEA^hwee39pfJ=i%$Axek{vd66eQKTkFbmhG;2aolxEVe{&vna$ zL67<{6mcUFZtYrMwhXV(_9-Ht%_!AzE7n}e^>$TQ&@+x4lq3w(EX>KBRT6@w4Sy|6 zh#qYO;NxS}yIESF^C2*%M~4*Yt?iB)bNBzM5VIDn8z|%Mw=3|Gg%N%ej9k)2g0wA4 z?S#zMwYA=>X;*%&B0#uj)A_S5xUsJSOsACUh2T>Sf|E5*yz)PAmE#yBI1RjXiwHm> ztT;rhZ;SLBgd2V=1v#o=(ZQ;t6j4O_wM>2WHa(5WyD(HI?x!MVS=kR)+86L*p8Hb1 z!oO?E1{`a4i%ziQ2qNw5*&hpiJ(&S6-O%!wQoP*WG?U+7pJ^L6cXWr@bu`$G)%bMO z8IrYx$oPLVXZ*HuahVZQubk9>y3=dBIKaERXm}|9`tLpF)c4uN#e@MUkI%*ZOq+Sx zPw^@Z`}PCF=EJFmeft$c*Q(@!=>i*r?Qhaea=>2T(2o4qU|^5#%J*0DLDpmiLO*T! z(RPS#6W89}s>(LeRx~igw#)bTb?h5B$9DzH8VPA?GaFDDg!6pUQ;^pGqp$m7Dva^7 z0^Mr{F8WOfW{RsMYwqvdcu5ny_^?D0CT1xf_amkiub+}?XTl?9NZwg9*T0+4 zae}!58YBS`TeK6s(qF58|9vevJ!)JBGRJ)NlS@r){s15QaNbzeva$GgqEx&1dJA1hN6fh%65Vu4|JG6Y-jMi0XW%9%WQ+T^&07tVQHI+&yU)wA z-x|0g@14oH+A2DJ$^|H?DM6@a2V6lsPLHnS#_nw)bCB8jJ3R7*M&tA{UrO-1V0&kW7ljsyU;FDC3Cr#Nc8}!g6yRXH zE)E1ydih8#WFpCJUo@+dnP=l}bScAeU0$?L@Uarfhd$+h#|I>f0A&0ow4<6rLA$~$ zXZUk&CU0Pt)J*4{)I#WfA_7~6*9VuEmv^9wkzjCi`#4kj89?JR;(GAIH|n&7)lLzc%IA(zuddd@yU@Xi-R~And?o@`y=|G z@}rIhiw^vUMLf^0Y3w+wr}VsIpnAPDuBCW?^y=~HG7Ohc?@EoJTbVHTn1tKSwDO*yo9$W`i0`_ z8Vev=F~nzNZFWsos_&QRe>sbUnXkNZM<&#xVmB?5x9giim(%)}?CEP|Vtx)LJsy{6 zJ~yHqvm5+Sq>sjPaUd9lN-1C&O2u;G?0Do@0@$tak^LL(ZbhX+!QkA1sqH|Tzm@F| zvqPa5%r_S(8>b7$oVKXZlnY;;9#ipOKTW8M=8=MOhNmtI2e5Q|ILY!hc(~4VJ6P}M zZg>)_i|Pr)dCWyz^OO7F6fSZqdHqlAsrWP0V;`sOCb+091w)UH>TR(Fj;T)zmL%gj zxIv5x6peJoD-$oW8xcF6E1U@*FC|&bvAgmadVzv)NsV%9y9ozDsSrhI>u^9T56lG* z>cmF&rb}0B`-s}EphP#ZJKj3jUYn&x5v6OhNr(Slh|jiD&$#qMZ*}`Q^y4S3)rV=l z<}Fg!*W3pT7QCqoh5JkRs9AS(P*C59ur<(D5^|%-o*UF#kSMR&*DNcWtPn`isQ{)c zVkU;ep3o7{Si>;)D!y`hX9f$adU_$%>kK zLlhWZ_$Bpsu>NhcP;a4UVpKDiWV=-@@Whl}_j1>c+h+cVf zb)WUuaFDkI$*>CCrM)0`pQ281-o{RCtPe7o0u`Ln?AkGXKliQ?k@V9rJJi!PnH-w_ z7x|;;kJe6ppfdhm0i@#`Mo@^0I2BZ^szORl?kJh3+vXn@xsiBb< z%tH~tCaK0d(hOIQIGpz~WI-Qy%03C%3B4#JK`Jqe@Rdx=L;h{*lcdh)Ox(C(_SY}8 zWw?oy>;>&xf~VKxoDul8cFa|SJ1ha8Le3ckG5IY1z6hO%Y{A`-OOOu^Ic zR=#a)Aq1H&&WN@(D9_=Yv$TBV)$?8nUzU9$#@hi;;G_hr5||7S0|K!R07UuQcLq#f z#X4Vr(TF4npN!DR0A3QL72mges5`q>d1!H-EionDQ|)%X9{-0ECYdpV1a8bmD;qsK zWQZ7CS2&I!n>wx8JI{w`v)rRatHKffBrekY0Qx(#CQM2+7#cGgpFbrWbKpZ8S#RRY zsu!04=1JddB5jaFWx9R4E-^7NJI(f#o5?#Xrf5;0S01KMCe>K;XymyxLK^%MFRu+) zcjQi*K%PF^P`vdNz9&@dwejO6p4Sj|Hd@C7iHk~x3t$u(-|iS z0ABPZJYfK)I9~eTuy*T3^GI;r1t2=P;9tZi<|wD9uOv_JuYSA6q)A8-Zg>e0f7{JHXbi%MLpATlW46_ z>N%mOYK9;&Eg(VVuzZLy7J zYT-l9q^OmGWBQJw-SX#@t3Y^Ei@vs-L6PX@XCGMH@ydmj;l*Xqo_&X)zey-0fq=s} zyS9jWMy+{mLgf;Nt9$!A;d?PxIfYJOp; zfk)_Oid43-C^aBeoKa(GEH=}BOQ|nHrtJ`*ggusSub<*eA+LTD^nf<8y6<4@jcc_v zKHcee5p&z_dfFc_ixgc3cbD|rW!K^UUt_2*O=qyIqDQ(i6S2mH1;)JP%DkmvZDqy` zRbk(KXhti^T&kYu=rgsNc7DG_ksNwpb_B>5!4vRWz0UQ|ZSeOQKRIgL<~}8geu^YS zI_=mm1%+&R7$h7YyszV9N?{2lZ>Mw3;isK(E-k11fdOo&qW7wuN&!J8GivUh$zv&9 zduu~BZtX0;gmNU?XX>m042W8{`*vj&VhgihXb9_#qgLs=Nh3eKYEpdZ8kk?}+Ux*k zmXBmbq#%Zp8d_tsAv?2NWZG~ddL9w%(862G!SqS7d{(m@(jb_D8cLt}WsuuM>(ixCuuRKR-*VDS9phF{j=KhW%2{{e!{(V@fzhU^Q)vf99 zKyyWAZJj-F@4kMTQ50fYr^8sML{}efsNdzdv68P_jc(?xz5D4p%zVpXSC*#c!;k9x z*^0Aqp^{_L#O1eSP-S^qEKwZPc{JPDw~x@y3B%n^TQp@w>5m)jpx~=tv~s2)<{hygPWrW3jD7@NFVo}OiWK1VG$e<=LUJy++mk1d@8z>#;|g_wa^4zVn)4ZGkjztZ!3Vgrop z(Mm~6H&dy9*Ft$A&AM`;{c?NZ3qI4sR(APXAD1=(Ol|h-c`?whUe%HV_z+)jQGMZ8 zuP~YhXhIgj8&VadZewvk2@JbgK`PEa*{DwSmTk4vkAQYdeNc(BIEgT>O+_8ttHI#Y(|DJ z)HwK8Qo=i`3CO!^IJ@^m|IjN5FBwdjdm`#9mEN^F49jm2C#7vIF6nxB?`iSXHZxhs z2k_T?sM)qKbLl|Le`xx(sx3bAtY`R1(9G6i=H!olWV~N|e6OzdygD zv5IqH2y#`e{Qbcyr--nIbg0`=DI%ed5KgOSagHpaiHvh2WE1BvJU&KB3Tscr3^?C- z6jXO7jXRl4+yt<>9lm$k82o^P`3OI-ycTkqy+S9vFz=S>tD1B0ITYn;AjNzGp8^yg zrg6lNd*&bv+XPQYYoUNZ@i(}4zcVGS0VJEHuh(!3aNdA+El5A$q#s`r8?NI~0rY{l z03JgXPj%zreCK;XYW_gc;5M&=y{%aPZ}&^L-oMl4@DV!P9`O=$jyxWZpMYKgasCQr zSd*>;qHA$LCjd7nGl2c|XswMbz#GcFM)hWI)IF@BzrX)w$GR{DVJia}lxz6^SET9N zmjLO2`MWe1kItv<0ZgxFCkP~v>Z@KOp$xAN|K32Y`=c+W{wQAJT}u45ATOZG9C`+t zdM4XX!6}9Ys)E*me`IL>54QSedlD&__VP@b z={L37n6j$Wn9^l6F5puHxi}*YT{F7SBDrpjK|H#AKLD{gV2iQdX15+TEFgE3=ox8< zN9-yZrH%$L?d}5Q#wKGW*E8GLQ@Tz82TT7-6Y@>?t#KNySKcZBddek3*CL5j?@OZs z0d#=e7E4|~STB$GS`6o5SLiLBXC)p*pj$KKl5s1jmv0`j!UX;A~%~9|At37P-1gHFSf^9>m^4=gq(@!`}1pcwsppNdxaPEg|Bn`UT*9q}hq^#p~ zE-ugiuGgxIZP*$ga}u4cm-9?!*Pypzq>8xQgPO+z_wbCbPH24pn$*nFXoROLNcpK= zMgjeg=912dmpjgc8rMh#_omx55E|f8Z-zwJ<$lk~Ev>G2z^Xqgd|ErN`wvyS>mfAF za`WOGHYVvB+hw)fdf7AAv@c)2*T%DQI4tZ`x^yZr9%gl-4NT_@8y<(A{sEFywc z&x7|6Jn4$}^dT27-bc3P2okr40)dZ8f$FtZxZAY;a$aG#t60D2|4m*ZwkRygTr%SCU*z+8{JZWm=I+cdPTV|L`U5$E|<1Iq8 z6!9XuIa?m0bqktPnca?W(n})wpoH{IF-BG@I55CtV|=E);U|11xwiCEqpn)4Vq!?} zaf3C2jKHrRX{wWugJOzvwrtPdbEH;lNyo%NpPpx<7TBtcxvDndC(7zhKVjqy8ZG*o zHD9#4v-E1rD73shpZiI_S@p1(s&+T9tZqS|M-!uh60}E+L}$GNG2^)}hCUm!(~P_H z`fyg6ASz5M+jct+>(Axg6t)gX^iEn}$_(+tBxzL*%G;_tSX`k%Gl%JZ#pG(?9_^7q zaf{A13}xDKi*f|Fz*^r^R-4xqVWl$L@3I=7GCOa)uWA(6igZrdZ)_$m&@C8vCS z(s0!(T+-yz(QlV1_GvqirqyK1LvW;3v!_*YeyQPf+$w>SdfURMU?luh@%nzzP%^<7 zm(T5G;q4tNX^$t>?e#d9HsK_{uB*8{JLU%4=OD!t}u@yex2Q%EocTI;M z*hWj8G~`$j`tUn1leD5yXYxoZz~!^>$bmIM)rr{1rfvw`=C2GfH*v2tBU{%ld*x|m z>hjc)7So3xr}95fM4}tCTr-a`#Npn>|IWDjf-u2fgRU`%NnfVtX)Q}INO|$PjlptG zIch;~8WEnU+wpYPyz|ufe!(0uyV}KER_9A;8{$hDLaB#Cn-;0Vp@0u~MkGV+NnN+I zP#tVP?#yTCfs?C(m#vJCR*q?7wanjh80URciHNNjwh;lr#k4~TMSyY#!C4j5=UF_yo= zEUHe`H7A4vxvXxifLhN zQ9Q-V=MwD5m3#^VM4E=gOvW=FHbFB_O&&4_!v}u)h`@;ds@zSdTG9P?>4Mt&^WVIC z`R+CX@jS+9+1dD0wL{o`OTT<-POoR9ru2_Ehhp&{#T`}q@tg+%-EP;yM$?4t}PtQSpfFdkD_;E}h!u@@e{PS768N5%Yug@G`GNM-j?*nlc=O$hW2^ire2Qube0`x-nEgUaVK#4@#Dv(Fz!KY>Ag3zec69C^v`cg5MAI_fQP$V z!Q%=Fi~Wgzx31j=H$zclD=tzt2fLoMix1E)%N<-t54nUNH_2xc8nlLOimki4v5S?Z*(oonMiOjL}|68E8q$4G0ZF%LRC z$uO%~jMpNDRsD_?djCI_3)+yuVRZQ|d?`kK{^~%&iNi!T%xk1tNGU##cFmK9QU_SG z5taUDmjHw8<;T_xssG=aAvQ>QCm-djr_XItm{2uanNwXwHC~agRF$s^`-Z3>Q?KCv z(-10M9bhr6C!zyF&1GIjM9pKs z{k_dOG>u8$plqMPjBCLQlTG|1Q77tAy{{NTkxQ+%K!L3$tOMp(Qf7xNyvy99!en*P zwlqTo=5&fb#qWJKp+*=8vY*k;2V=JgW4BJxCAA!VA?GvHbhE~+u8LtOZDI3_J@uEB%Z)PMj%k>;7@K1jpGCk+daTe{VahH`r(9 zk<^JFH%Dw?)30T$g=qjpO9Z z9%nb>=FsD0w{rz#s>zY>j~-|u=Cz0R^Y#xlS&TfrPewBGYUaB3$4#F^`g!Lx9IGrY zISJaIO}!nTvb~UL4s+4{TZA&Ishn|Rx8IlmO3%Ko-ox?W+{Cmw&fV(0=6@Li+SK!$ zuI7LF;m4@2(=RUW9{FagP^}yv;2SQj>?Y8!txLOv(s+6Hyg2#ZAhx`{Frv7_NCh51r*QNK56Q>GG&Gr6t{k^cfQ`|YCe zTUnXLn&AHLDtxjuyu-NWVG+q4vV0zNsU#DdWs>T)X4YYvz)mx_@c!J7KMzh%GrL&R zC36%iv<9mRncqL5%+oUy;VV@w*(f^Lo|2dz^{L&V0PflzKL7cSv<1s-@;w-i8f=(s z_O2UM5c8`+$koD&B%FVG{IaQSHk0J9^s&%pe@G<~B_lbbBxs_DPft^|NmFKa5w}ui z-cV-#Iy|4Nj`kFPt|e|gXTTQ0MuXy*b%%f8sC<~$`Mj$ssZFBZh&yt%sI^eXKzBCFr0CQ?c1J3SrSOm9d7 zsB_p1(I3_~*vYHrPD<3ji$h|KT1Zv8{+_dgPZ>ALbP8A=9JGpQh+ZrhPF=}O%gEx` z{tzrrMW<>ynX1MLXfeAz;;grnt1L`rSrLN~hj(g`ACa*6m@557$&@Ot-!wkR-fYf; z&v<0p&&I9A&c`oSlvdZKf86|cEo)7Ppx3hKtGL4qyzHSd5reDES?39zeTWY1scudF z>`b@&u2vJo0(b!>&9^0c5_z_Xr|zLD3eQ1~`<~z!0|cSC7x0>oD2mYDRX*uqtONjK zL22=!>8E&$na|%Iy7T{D23rvPMIRfkZ)F812!2Ttbs$|M$uRoYACzvg`xpv@oBE>k zND2zYYVkGYC=B3(0AmO^74Y$jMonx1l&eHK1H217PV!kP;&>jB6J-YhI#A zT0pin;lBH55Htgox|gT@ zz)+9p3X15B2nA^x%v>S$8xj?fn-6uR-zL6@L%{fqX2C`pNqi1O7Abxcc2lSAaeslk zfwOLnUv9CX&Y^}{Yjw{gUaQA|L4d>`AZqZJh$CChU1QAMqqYhEndszIkY9IwH2v7*bEJakNnuV4H(lt6Z~&D*R2kv{3=$^~_^M5ke3vy&2k??!^Zs_9 z`|x!1f`IrG;A}Vw^b^O32o{i@oC@~PyEPkL+*2#r(>xjHoQ`^5qF6iYy`%V&seW|0 z2mgR>T0RCp-D*iVED7Wrlk_mJemQ?1eBKF)Qfi91lyZqf53RUksr~x{W5j+v=f^LZ zALz)-dt;Awlb8Ltixb(gJ+`rZsZZpXq^=tG`(qZ<>!o&S;rN z(Ru^Y)$m=LtYCa9?}0?jT0}93RCg{j1<0X3AKM;KenD5~XXpneKisYZA3fW(s`sa_ zJ#ZHF<7xTh=_wVav<`~F-?EnUcd3az-!YqgyIHg)V5;sLES~AVzAHiUcmWe=yN5|zoni4fG{_Z%1%Z1mduY3#M4&1D`G!42v9 ze*bI}ys=>atulJ&TUGoa*iO>!TALEQkR97>GL9H3dZrwx3?LSl4J$?lsAsmJs^Z@uIHI-p<Ao$MXEcS`>EBh5&gv-pI*LOO~a0n{f00{ zY&f;X>i%oXU+;qco7dLfOli&>Pt=@${xUC|9v3y|q4<5qdLx}SeJ{*YmS1{537O?x;Idh8oXV2B z%FNkvg(g9&S(7<@->saFK4X+~4nM!uOm4ZGRF902R&?JV`7Ym7C`3^%pY(?72Deq4 z9(_YyEH*oM4ZsmyETx(Sg{rv8c$+QuBio^j+P)iKTRg$rzXgd$ILlO3S0P2)CqFg< z?e#J~>7^zbnYbiw78~vwWdT(-TD&}?&%KxU_c-=)bge?rHu{rm@O3hp@c^AY-S>Mw z=nDd7a^4m2x(ldZCnzebmgidFHL`Es{GJI(^k*ritt`(r`Q)`8%qyNfXE z#2a!?ym~UccrrZY{}QNWU$Eoy)2R$n4~q_NFGaJKQP5yGpuzB(?Ip)NlS8}N$*T6y zfRc5H3)74cSyNDvemM%mITjI!d}@$J&?Ntacy@^>DUIS{0YYCXN^SO_WMJKeKuvpH zTIIY|MkKK}i5ATe^Om}Q=IpRD93lqdt!_;J5DQU;D|32=Y7hB(Hd*`Xt+vT8)`Wkv zTXjA9;ZJcMvDOHqxsM~Qo<089o#uY8V81L>XIcEw9a8?KiKg-I4GP_8mq(Qs+7%ol zg-w1=5IejPg5m;3u!IkA0d;MJMDi#|Y!kfhnXvjBo557L=pj4-y{R?q^K$&L!ewX! zd<|thsB-{i0#%{J0D^IjSiXs!I%%f4%G1fUG4eA|u18V`-Jq;L`W>w_1(ep~vC_v< znu(DHe$Yh$&0KA+tP+vj#*u_0l60asjcQKEg3|drFrF=^{;K^@Mi^oF8*dHg&2QK+ zoii^3*#O<=qL7{^9z@dk5S+)88a+JH42}UcUz4m?dS8+Yr1Mn}Sty%N`2jdLZxS(^#jB2_3{Pn%a+)W=J+IIDM3a0^CqS8aXQzy7_4*9@!H=%lV))N! zc5t5+(bugMKV)f)kfY_lfrxkB2{KRy@0ZihPbWc`zS-06kBT6?i6;hmFL#-4Qmywl zMQwSdklUkpCvT-DL3umr36gX!ucS_2Fen9m-~|lwlAJLG;{wzlaC#&BazTxI?)KG} zOZKfH;)=fLA#niU;q1MfjBZbdz4(1)_e*Ta@L7OhPwtLrFbvV`Ekyd_FGD~M_*z_e zx4Ld;tU4|^@a{j$4Y+t&!9#DVWL*q-=G55z%6xI-bxn}~3 z`W{7!v3%<3b?_hfuC`IkN?`xLr4ZMsGTPO03D&U9DG@eg%pkHX#&^7TIR;<)aFDlM z4X?ae0vm?4@iUQ7Jf~F@y|iw2fc5?7pJP`MlzV=nKEFE=!ue4Tlr+gxZgzinq0;=n z#^IOKG4mo@EHWaHXdJc9Y+q$I4%1Vq)QhV!QHSY&sz^`Dp6As!%ZlR|YBS-fvZ3FB z|4k#=Iq0KpS&Ywx)E?t-Ne0)Y=e3NqqH)4Ku9x(`Y5$Tu5xeM>(#zE6)%D#O#RXLF z;R+k5=<2DY>#9+{_emSysvs6_ zws*Gr%kNAN-^m_^EaLS#P>DIE=D;#kI5O&;C^r1CNw-(~sB|aWrI+n68}zKYvvt6f z5hIp6F`qj54u+f@{+ z&mc^KgYY*sTMp*dsO&}5zMC(GsH{N^eDVo*$zcWV zWgFxD0PnZcOfIbLvaxQ^=&=Z_o03k>;;uK`y0)!Mw_FnK`2_5VV>lbVW7JWppXN+op$&@= zB@(McxIi&@UR`1*rwhG{NI(V&3jD>@bKu-aq)d@}-tV%gkNKw}jq<|jSa#6066(HB zh9#XZmfhN0C@+p9B~iq=Ge8^`z-W7J0J$&pF#Rn(Dbp|`XBw;3?)Ej8je}~C{h1Qm z!8pfDbj@$&cTv86mF=r~R!JD^b9vn8VpV|cuzNT7>vak-v-FOjR>nN+9QPLc; z^DSxF=qUbHE4xf?3PtYk$HiF1;mgL|+$&#!l<^{!uZxuvbGn##qlHK#ZE+Rfo+OkB zNPhL2v=98)A7Zq)BOsWc63$q?mboWPVPF%L*2+>gzyIM*C_B+0CN01~`-?LRf6!<` zHquFn{`tLuYw+m6Oz=ibN1UIO-LLB~iT zYGtn^zAJ?_$tQSuP#Hr6FaavK3p@a@xvq39B#>)962|!e8nKLsX`;M@ssm_FK)ZuP zxj3p{(*1%i=Mbit55Z7XD9iC9!)P#LFOy+6U(P5@lTG*vJR(bd^V!=6@Iw>-IOzr| zFD-fV#h=Z!-~nJ)f+tugwbP@Ee*cY+j&7uQbw1cT%K9cgtgIWE^SRZ_4w3f{^_R0wHZN;mFathQ_M{{qo`>FZJ|K8P z{yd0#TGB}mG^CzFNf#lUojMC_AkED*PmbQVOMVAP67dejn8cTU7DII%)}(uDbrD)Q z4gC#K_h6u!VY$)uSi4VBBE96A#kA$J&?7dWh3G%1O8C_-NYrM|!dj6uY`~4SE=sm- z=Z6+8PF!pK#c&{?y<>IqH^|)om{?eGkm$Imsy7agiVnX;1RC%S?&BYlY{iAjC-+}q z4;V+gJroX-&$w;Ti#mmhvCRr{9;~^2K6qKdG%;`wkqjv}iE;zrl9If>N?hN)nU=A% zk*qhkEFv%s-ULTAmLsvFX)#7`{WrbHlQ_fy30;F9os^ZpkzddO{k*F2w!853_u%Ry z(rNdYqq^4v=TP4-QDI=0*GYf;=OB^Aq+%^geZhxPB`vgj+byjB@I6kOTc5bmZIAxK z0?^3ixsk_=T*j)e&_6|w?iyy?QuUM+mv3A~-x;63Q$7#rH>#;iG?g&X5kP6OuW0h3 zb>}6;$s^zmkt#7n%}4D8j~5Kpv6vS~d>1U%;X$Q74=k4l4<(*!WyH}ZdQ1SGemH_V|HYt*Mru}xG zl@*nAiAuVliwJCbhat9#YJF`m|W931~d&MCa9r>v( z7~`6vAnA;ArDm>HWrx~dxq()$@xSm6PHFf#zE@bty_Nx zpTzms@oqAAy|TkAp#xzQ+_~a=Z(O~QJ1K7fsWy1H#=l1i6e~9d5x$~9ze%6A3x9u~ zBUv$I(oz+wqoUKI0juk*u0lMYoH+oS$}RNBja2VsJhIIt@)k5Q;5P91I=Y?Ke4{O> z@s(hDD1TMA2!KC5tq)_;vWF~8J3o4xGv8DZeXzWpXQS!~rTorP zmrpoLeVvJNJmqxXqW&t+$#ZDo-M_ES>RlGK_mytuIe~%cj3JKtt9xSR{(TmG#hx?5 z3-`I6-W?Ou~xtlNRqi%?;}6 zni-i`WYx&0gWpcn!Z!_vs%v6O;Q6UMg`09yf0*-rxwu#>_ZDVGG7*3$Lj6KR_zQW( z=x8;ZeHe=;>)>Mf&s5mnywGxBD;VrAu)@4k@2{cJ4s0ygg(b7-yXvw(#l~(S2|{Yl zCsW~?d&92TZR_{@kXoHB19ZE)tl9=<&dFh;i7>&{3;5>FSxADByh;d*T2Xt^=~tX$ z&OZWj13GRKPB?Q9GUb5-0mRZDTi+x}6!e0EO3Gi>gjjsBPur}PQEUZZrEB9-P&)t( zzP^ey9TZ$k`1=~X3-l15lN$z1{YUp$#@=V`MGvWjxP*uT{fQQpzWVM5PPVmA{vU)qnw zmyv45dj8b@9QID!0qgKBU+wTbUrX6>8s$yTNX3Ka5Rp29+q@F|fHVumVit*)onV*F zIt6nEx}YhkN3NDhE7JToDS~emGie&5t=%R6gX~-vB?;SUJjZt2Bt)lKmv)Yl4Cro{ zJ~LnM(%i&a^U&`J+o@ZN3@l;yB=5)AE`syIw4&j~HdC@eVF7u{9d z(*g`wjN+DViV8k^;}aJINw*gDd3oRuxjmE|RjBDxd`&I-QVd?KNaA?Z8`0Icu)H(> z6hP>EhBYMlOwEp=1$T!)=$6a>oEO7rfon#$xf|8C;(lkWXq8uqI!jolUF)y1Q;mwh zGRJwYWjh*{A&vf*mk^pRzcZD@&+7+|jqWA)E|&VjeeQO74_9{-h6yDK`r5;H8DNRI zwSsS1X0-&%6fc&JrpDYg?*4ZRJU5WajVk_7aqX$8=g=01eLQSad5jW;SFS{zD_|BS zF!iY@8&iSBmSlhTsxEbN><3oJY-$2fsovdru5QyJJfi0D8Lu1Y_iA*j4gIx5fKG5r z#pfv~F29xM(h~6Tr*bgYO0ufT=XH%=B1J1dpofs}wexKBmu=+p0{SBA6l%-8T&9e; z^`54{m~Ti9e%E7$Rs3g01!so%^8ja$K237ZECqQQR-p)^uufkIy*V(a>b)&aZr|HqJYC;q#K%0#?ZSJ9<8!Mn_IM=vj1H@aw{i_w3b4(e2^&+pqAxn9*t3ECLBtb?qP6=ii zoKt>&=+x*BgXHP==SOQ-@0H9Rh}0?`e-?J$+!9kRqahi-mUX<2BoG^8`+^X@+>&dv zbzD4=$DAk{r`sE|=VTy%;MCQgsZetWCSq@2wYSgALpMIGoaPspT@F+=u20QXP3=|k zH<^;}W%ug{3NuSlOy>0ln(^(<*U`4=*)$fl_f6p=;;r7%D zdUz+y*X=zev3of})L%?kCQG=36SsLEw{;h1e^1Ezj$~V2)(CvOF3CACr!VgCj)6!l zDRGXH)|E{h;ywGJZZh(zwNZ|Q=!7KZywAYX{=la2%z10ajCKB-9C?PhQ7Y6_O zD+GBSvxQ%f$d9vE)!W2}@YLQs)FQ56je@Qa_j-lG-(E7T5 z;In~X08S|NqaE=FCpTx($e?Pm#T zk~cBV+?qtkib370M`sKYZ8L{Q1Rn7xM*fNZk87XM?h>7xbm0yH5|v2VijyLYXB6p3 z#eta<3!sP*3DSLF3_$0s9PCO)y3LD#T;6(#UW zQ4i2>F9(*Ju#dV*BXw{*n=QZWw2qGX{<>ee?D9X^wRay#yt9`8UrN|SAE16S4Q%eB z2;MxGK9p<^OTs>^+Q0w>b=Rrm2P|(hsWB#rZYrV^vQ%6wHzx5<$A0PJp8T>MO7g5| z?-;~djRr(swtpt=tFYNJAt$kR^S_e;pTdP0azz6?9ssqpQaHsgHl^%brCb#G7l#=> zMl*d9EdtYrOqlx18wP>vgj+ViY9ud<$Kn5E6~X%M>FyKpG1&71%1o?KqPEYvjNkd9 zb&8IzN1t(nWN@w075m4t`>uett-);dPt2cbEkzPFVB0`yFqHBUc$9Cs3)XpC`%b*| z-)clCYc&N|(tWs)($SB+vFhh<0tWg1h*_|^isx1x7tiYDuI6Xb^o%ZUze5IQ3h`j2 zZWz4n%UfK)3tT{#2*Ds zCTdjCWND9=(7!u^oy(e@hp3!e86;?r%f}q1iSAqC1w7p*lLIBs#cNciyfl3EG{m~i zrHumS1X8Jf$zWDBp5sUpC+ind;dlXy3MXrvoY}2tRXMHoD-$O~s-oC%%(nN3XeyWd|y3p$pWpHG(vs-$QuTd+S$tIdU|@=Y(oYyFIo3I!pP|lz&;8vD${O!iB|+zN+fwh)K6(d3Qjc zapy^sJ8H8zM=v*P@_fV6l@ahkf;4(B?nK8?z<*XR8?ld8vo^jSmeLUwtCoY8LxQxk zbeH9mx%9j_${ILq2{}rCjahL&f6exrhm9Ojk=eK-ZpuqL>_#jbY5Aj1o;i{woy8WX zNA@M#+gQBAOr@IUBwUraXmlK&aom+LVWJ@A(vq$NvUEPc{C#&5%0Bc(wm$ciKSp4C zUCs8X8gsEgbSSfY6meCyCVq)O8O+-@p0%mC<^ZWp?N$O zzhAA{e=0sDbbZW;6omKeXTE>8AzOR`+UtK;=00O2b#t&RmYf>WmCDl3^nyMwIozkA zp)5YpP51l7(4<oU9D)Q1k)NES40SC^ezDyVa=nf?KD7Vum~X*|n}!TOq_ zY_X%L7Jm)k01(F3jR6ef%0w8(8u1#EDZncz%_9#`!MniJ_)R}yL#1{RiddP!LxO+v3h~7Yn*FIa5CIee)hd~9v=|+?h{}GKkO5~!3w$K{`WB$SE4^?OG}oS6_cT2~S`I*G ztII(NUV%zVQ=>Jm&uBFt3oEqt@JUn1NbGSYR%TpQjPH0CPzWnX{_#w(W=Ja+I-Q_V zbnnO_I%D3U8?=T*7_1n_dV>ny{QJz)#?(lo`JT2%bhf`ZoFD`^(#QBE%tAs25)b@x z#(DUPcCHm4X)QTHy$N)f(zxp^c&LmK6}EE`_fYKSE#I|9kA~hvd*4jo(){p6Ye-IM z359!OE4jG^kdx#LUYkTORWo-p&?(z0C+YEaulTkwmfD;i_Ps6Dd93Zvt4+|=mwfLv zhVjRdbTdDfWMini&-mvg&kQ?~SHt6%vIBcMSQ~BgTmCX&5h4g|;4y4=TZYm7bao)> zk(4My|AuP}2|cQh^oWWzHp@ zB&~?*0R#i)+&vCcQB0j92m5@Z3|s5DN6V(L$NS#GbHRTCmAGqP*J3_Ue$e|?8Z$== zpfZ-6OHoX6XlVkwwCxOr(Mr8BbSL$@g6f^Vc|yMHdqB5HijHjO1&V%3$H1Rf=ZETV zn{i9iX?O-hGVOmJ{4Dw#hQ?uB+JWz5C6`f&Eh)iQ<59OhFCzn=y;7#9tLGmu{npCH z65O@Ze^?lr?)Tsi#y;@_d(z~aL0~nk{{!D?#9ia~e{V_0OdOQs3o$+lhf9ro7oI_j z2a5ct`7OydqA%%DzED1R_op&6yGzskXHZb*cR{suzl!`^-7MeVd?_#%WAxN~C8QSq zbH}{GE5ZU_K+Ug(gFoM+m)%c&b^rCy%a@JypPnwNtBVND_#rF(DiCfJFf;Kg^(7yb z%^CGM)qyUMaoU+W<%Sp-K*HPU)cPFd4Ki5tBcV27oVWmM@+^9#d+C(6fgE(U>i0~w zndWpQR&}_fN?}cS$>3L50%c`B8fIl@ymi)y5@MgNcV=b*YjV%hAQz0==^{L?5h;Fk z#cp-gVS6Qpn8y@-p9*b!O3rrD&1~;NP);g)EZ&yuceHtS&i0fGmT1 zYr}GnVK6on`5MxpWdAKZe=Pe{=HwTL6zR5SLK2B&?KRs^)CFZtNLna7w>&MwtT3J@ zJUZRX0~@snZw;-0SlE&&Z9L^N3HtH~-|HreXL?~LzjTY*Y^^7s`VsD6;_Yn!W7(vk zob}|Vkh&7AWM)e6n|Bu07_&$bccA?SsrGwK|7TxAoML<2;wkm}j4h3_t)w56g58Wnt;5~l*71>i*dO7WA~z#w)S4{DWCdMlDh^|-41^YR<>vrob*7{|CBR`^^qCU zHH(##A&9h;I}lFwej~N_i+y`MhXTx9W%+u~33O?g;!#rQfvj?mD6cby68sv+o}SoN(VFF>Jrtn)*Ra30!=s|8;G0sjTD0nS$?2a4+73nHkIZ=W zJ!E)_$O$kpnNR;EuNPaU6g=Gk{!|E!dz{26ys2Yh-Ses>cGQ~iGcH`s5`6ld+;dv& z?iK&rpkk0hB%2X>cX}3^8VUwh*+2LFnroZvez8coU*7Tw~EDxv3 zJ^A6|Wn0oe^H(FXP=WlBXpbcPp!{g6<9?8^G<^YyCieR@9mU!3+B0cj&zj^K{wEMc ziR9}l0IeY-5Lv5=J(J0Z53U=909m20X7=`CDd~cJ3dQ#~C69+1=0T~)biX@sEZ#xw zq!}5=#Q~WgnV%iKh%`vXPyT?n+~$jUse}_5s0o%<2*S$RoR`2Ozzd^-_}7X0sy z_&+J%FC?AM-fmMRCx)aB@H%Ei?e0WKZPP_|<)(~Bg>3>iN2A@A%GJ&|(}N+G(n9yj z;XsViMuc+zr<2LPsOVjlaK4M(?;_rodne2Yv#A=0=NEkl^6m@ZnTEqJ@z=*5)wZV> zF1K|~V$q`w{ipELTBXwy$roo5vwl}svA|s%U5PW<`z@pHQoQca{Cu0Xhq57O^Ky&j&<523xo&(r$VmO8&$G9P=CW8^_vqCJuvkj(8?u z=)SRl$JMEC;|VSWLT z@a;Wv=q37AWqysq3qmyAi_EUzbqD7E+xvA%d^4h3(0aN^9u7hVE?1=vBFGrQRxoz1$8v-P{y9KW}NcYq9bctNSP~ zI~Xi0{VJ(+gKwAQ!AY0&PD2Gw8c5pGro{Am1!hZBC0Ow|#Wakwo=+129JVae3@RPV zj8Q(N>sT6|zb~RX6crJ%z~y8IwVBPIfs5^k9+ri2&nq-nb#2KQU#C#{8aXpDjN5oD z>2^-W@y#U`~ugc6*6H-he=R-ubr zZe&_sv7h4`Iar#oHz8PM&dZ6aaxAZS#cj^5P7-UmnNp{GnPC>s2|tD(mA{O6NN z*WnM%Y`=57+$xauc87USRczB#w{nr^XI6f6V;p2koO>GVbgG65M$pMg5%&dAMR>Y%?P{Ei)+8_WQKH{%Q&4_0ji;dUB|#uwjOK$NHG{B&^6& zEO9Y3#js-!N@wv@nwo%`GSNtinQzwrIkN|~x=mVa&dQg@^)GP7FOhq?nhb{N!mPub1}X5d2~WMB5ksxW%ULq=^fN$2;t~z?ti&0NfMk6IIc2nUc$C%2T*o@>Y0>w!NI;o^`a1C^l(xWx>_(gf0!^*hh<0NkHxpaby}alZ6z zR?orEjr(^Z$PApMif=(minktV@&T(_+?vTDaw-3MNyFCm3zyHxT}#c2CwH0tbZ_Fl zE8^L*%u|%u{EtWTaj3)p$JJYZHTk&l|BMM!d=V<4q)khAi-1Z9(hVXKlalTM0tymJ zcXy1gu>nehj2>*jKzhWe(Sz^apL4$Fe9q?|*bn#FIrn{C*Yo*!aQKp0W&#iUk^b=> zMy&sOHQ0_G*!0c#5&PK5dOTy{qMb6;NVecy#$aU4C5(8CVT&(tHgi@uAB*E*jBdRG zto@2T9&aX-_jtId2AlWVDa6{}gCyEi9=%o%8hquAcX_x8$?fE>CNVa!RHXC;DQGoC z7B>8(H^Nsj7_i#EtR&YP>p!eMxadN=dFM)AB&S7-8JB1F^=M8_;OIW2L21Q&P2zXJ z$B_?7YJRxGE5y%*4D3dyP<;G)xJ|XxsrRa_GoO?t!lR~|4<93dx%gLMd3AITD;yUY z6Qg*4!HY*Qc4tg6E(Wxy7i!;GXr>qir&U)VHdR|*eT3T_4AEroVB9+v8b18YCZH1$ zZ(ouzM~`pzNqa%rz6^9Td^v)Rhbf3>fim&c^PF8{OOYN5FLEzVHojeHxm^D}6g^;o zA@E$UwWas?Q}!Z3C&u!;KwdGv@olvAjwj=%3-iNDr$~7yEZ4UWkP94=s~q#fEEo&1 z_nrUey$B=hEx;P_qe_9xx;k0cbG(E+*s)27L4hYem{q3ShNL&Wukl0iQRFU*5w(fJ z?t(WfOqsWD%KjFj(naJyPWI9LFoQFoKf$S*L%tdg;>UA4lh%KgoK=snF8Jj7OU-!|*Kp{DHf|@Kt=(a#i&4{E3p2*Q4CGNtEekTAfH<7_Hr%F&k)U*?->+mCJg-t-WBzU-K#qL4-xWB~>vAA3e>wT2(pvg_bkLMH_P7 zuWCV%92tm7$M6A3wc(GB38&au`*S9H@zD3|87~`|aZp}TZ9t6$16cQktjo`VGn2Nx z0De=C>@64kpJ+tE=VLN?`OhP!4QA_T$xK-P!Hc>t$*Jt>hW4AklEmeic<-0DaJA%F zEwp|#;5lw*a743yPO@!jix5ROOQI*p$iQXf0$3i9Vf?#3Zk=JT-kWrR-{a^!n zQ0yYT^~|8L*+Z&qyWKL#$Z5c|0S z8F#5ZYqdPQPm;`BW+;b=9jR`ou~JhtV>*rct5TTmv*~-VN^a=hK+S0`Q_V{jZlLcl zh<8sRq)P;T1ZZ3%aF$6HCZp5>4<^p*$C-U~l#~*@6_%ypo0%Q&NfK;?Sn)-9lxlS} z__FthDs;%nJ59mKEFxEPP#~+QOfu*2KI+E zq%#v4(hMwTMb|f1AbX&j4GO90U-s>NOxsUhn$LIO7GsyT&NvEyEZ^tq@hAKC^Yv3! zuHOgW5BhI&@L8N#zLkf_G;Z@&f1vFcazOB~29butZHabfivYo7colh)7>O#lLX=K9d_ z;)3ju87E9r>z56ikxg2pa9opbe6;wZVUa}^KOoB{2W^dzz=q8MaH$_D6>Qhup_$kv z<$iZ5^9$Y8CtZ1>s>$wQbEfd9H`zF4@E^G$6)1;q1Q}#98gUtT(EHQYJ4NVriy3 z{#YI_ap2PH88=Aw4$K)~{$w=l{KLm0#>=kffwRB1uh9w{QT3LU*h|tNF?RR@1>3qV zjLfwt#>HJ%6?7m@`H1JCmQ$gea>gkg10^upH~t+=V`uOD!=3$JlOnQa)f64|inp^r z95mR0^|#pPufr;{4=0n(7v#owm%VW?OUEtEluJZ5u@E~IiZw5-;Kekaq%Iqt`)$4_ z_HG83O}U&Z^SAGPhA*bs@dgjsc{Y~?^;?(2ryqd||ERIjuMPrp%&O|M?vJQO*- zf{k4y4@Kc}u3^d9ZpkCE7f$EXfeL!_*Irr2+nih8PVJ=6=nDF?(Rpdtqpz`S3Z>8z zL)>PH=7zb8Szfq+-**eIbBDI8K<~G-I}aek|0iX^CY;5A206m8iSt#a&^E=}SNZue zS62*e+Y~N(r!r4vtBHLa)2MoNLMYQ!)vlzgM)N|85z?eq2U~;b!w36VW!V?hM&=)5 zp{CWwB-O%V9AOO4{$sR}6T>v-rGbkXzw_K-g=wGN5R&J?fM>-_EiQLaQP-X2sH zIZ_YRBhp*5Z-3Fzd>lxE(+@mI;2+eWpA=YpE>pt?Hg40Zt|$`*4^L(KI|yJ5xlJaL zcQwly{6Bay+=*v2EunN*?4ZJzZ$U%2XSF7Jf<7GWw{-;?JVp<*>;(GkpXMifdp zO{Sf;MvB+BhBJn>TERxUOP~JZVl^T+;VAUB7p^xKc|Nh}WH8d%*kq3W$9Dk9yRl`j zr!LcKf#GWw1esbk#zB?oMEdTagA3)*iti>9!C)64DIcV-sIhcfK zp53Q7esUSG&O8X}q!>yD&*t}NvCCnDX1gzL{tt2>cODYt#v#k}!duW~KmTxkKfh<) ze*afOb-#K_E27nP^De*T=fIXzGm;)Rt7FC($6tFz4tZftBA-}T*_u93l$p*nYx8KW z@ctfnKMw=|GiG<_t-okjBz3~(KP6a~x8TC4wd)m)Zkibp=C`Y7y2G{qJh z5?A&84yWY#+mD>uwvkZ%Qt67fT5?(6GW{X#CL+GQcK^J z&3@%L@^bX{_#IL_M)IeDV5-5xUr7S#(>^oZIiuaL-rsvd!3oSw(Y5E>v9jp5b2^FP zUW((ATtjt}V8wl^3{CPsRF|nv3z#3=a{QpHipXoYRDOd|6GI4bVS8^;Lt4S^5#3+bRRv}*=?7OVia46tBb*>_B z?yqWAAi&G}#pDg%cd*f~CjqMWK~psY3l8+MQ7fnzKbSX~?2ciGF*6+>^`B^4bBQ=g zSHIG*Ls%`Uo=1Q6?WE|gZ+qG9@23pqmRGyu=|2aUGl&W z{{=#?BvH##Kx0Mwl4ZsP-7sL>0GROstBg+ z)hyCNPdGNR$}Z1M+)C|{J7;_Snr)>>{+ubd+duy5Sq>;Ywd9C4H`a|b{81BKi;B!w zDCTNG7UYGac;*x0FL{R#qU2=IB6G$bx0&Hu;`vc4mM=Qhv6du zFH56?3f`qn3=5HNH@d`&Se(S&2!2@eZDfbqTf_q~& z5ragv1-Gh29!Yr$_!evNV)KCa`*s$p{&2w6u@MggZC?raU1bmk;NvKoD-QGP%<#d$ zqaX)-Gv!uW;OF|}tTVfFf8FJUz-I0}8RS&mKL3mCKZf#bV+=@1HJ8&pxmaal&Dm2T z&LyWJFOK62xNANTlR@|`a%F^Vo$zRMU$1j?l6m{@Pv2Z)&Sg%8=WetG6oas#+P?l_ zaV2y6Xr+V80SVY;pZab?yYa{L{QP|WWMfYmL@4UbAefePsA4+)%qySA?NYJyD;O@{ zBWusWVK{=rvybN>@~gvC_`8%L7qzSP|8^-7t$Dr)R1>(#-h<=|IA(TDXL#A+L&lUr z_z}FMdS~EMud@#Rf9|YLCs6oNOwMt|c@;LW?L}qaSd_H23ijEL2cC;tZv_JCM*N7D zIEr^|+9KG1#gE!_2?ZBNo$S3QedoAgPd{|1E$+jwb?5X+&UH8r{D(bQs4d$F{0?PkRD+vbhGZKobT z)8Bal)5pO&|BFE$&CJgRLq|2fz= z;fG&ZB0)(D{#hT+`l7a_IemeIw>pcckNrbnD4i9{;sncy)!B*(OF4lXvTQ#<1&e|Z z1%7iLKNu$acmz=IIrS$#wiX~7t;=WJh(c-g?vKw*EFX>F=)7%0JqlqoQ8aU*ASKmL zCa}y5m!E_iL(SYdnL00~rauN}FvleGOcf_+G?jj;DDfy>JTCe&Z_Ix;EskSPRv|!d zKXY$sQO+<?7a5rvN--~t7BDKSA2F}2XQDMzx|X<2e3i3r zv2-~mi2rxn(0;6Sy|ppqbYpS(8$iDgmJ?BPI@*v zPs{slJ*L@Vs*#&WFrDW5gcST~a9EaYswOP>Q+FWy4$~X)X?^t5J6l}Y+uYX3x0Rzh zf`+ua7>buM-;BlrW&QxPiFXsVv515iEHnQ+wk zcUQ1KEY5SDL^s6Lf3o=aIKOkF<+4D@&Vgxe+i>Q%v*nvWVU0pA1PR^$>lx$B zIBGv&jEkv!&`7M=yc6%@(Op%sj*+ZhEYAH`aHpv6Pm~M0zSWLN5j1AgMww$23wKNL zf}au3OQv#0u^j{hr{F+CRQrY>u_w)C3@d-)geIUJ=Jy&J{fHvis-NC^Nk*2s9{T-* z{f?*T(q8A+jvt)fDoao{eBOVXb^MD7ycrcj*g=N+W+%-qe+MnIDWUtp$486VSd6R-8~ZimEc(9Ih`u52y8 z*-HWKdt{V*NFWc{;{}*|SKd0~e*r*Y!1gJdGW#Oq*=Wd#s3)M$RcBSM+lR~n@~*uj zghv)n_7q1h>T6(4#<&111U1}=NfMm|2m&<#d89P`gUVBg>g2mX_OFlm4eUGl2ES^? zM_if#|I1^U_Hv~=0N`5sF1~v|cl~dJ;rlDIERy`eeiJzO4?f_D#%=ZsB|{RCB$RiD z&x^K8_7ynjRY6Q4;O00D-<~}aS>42@xe%Su;6w+Xl$7Q;istB}lh#jWnLzkAH(!-ix-eM8%X4qZnoFNMqx<$XuH*61L*^ zH^4%AABuA5O0Xz}?qb)+!AQfSo-K=f&W+*qk~R72nhH)+DlA~-=?nN<~{#i z)E^&~oEBXUV!a)17Jr%OK0tK5c$-xpkcIeAE{z=rUYAZ}dxpzj!Xq2(PCDU+eMV|X zdf6`lR#nG@-0Z`QAwmeKs&hVPtkF&YHO0|tc@d{j8s@dBwo>Pe#iy=ijfdq-${^*{ zmx3t+0u8;V1;!>UX2;&ShO1zKFpq)57rL7mPLIn)CDPHqvB$*!axVm6CbI{L-Q}pn zd;c4yHPc%F(Fivs`{3OIS231ekND=O)%{O9vw$_e_HnUWIaBg>AwkP$Q2lFX2kcMf z^G9sH@r?kE@iCb5)R2=IBa;Gmd(ZkTAN~OI^@^V zj_k(ghq&BLQu4Cr5Ocl#f7iz{+k8f2+_}=N|?HCEs&^;FmWS%wQic*7F;Y!S1Uc7o2emGY*V_`X@n~F;k~TM!s0Iz zG`WDO@|GD!7M!?r`e#$3=21n3F~7qnzxP#Ire$Vhtr$jL^XAvV6}9@SD-Goi)9o4W zVOG*97@Q$^WXh|}!a&0AR~4;d_GZYC;7c-Urq560A)g^{50GBX_H9C&kH-xDNr4V) z)@-QTvq)O!`f7y>Uvg)U$&z4AGY``_ryXYSu65V?(|Oic7_q!eMqA@~_Tix$Re@C* zSzCMn%3@Ma${^iMNri-NbR;w-1mxx0^Q|gc)asEGEMAInv=6dDCj~P>R{jcmvkKDz zJ`L?hwssh`OJPt&GQUabYBZCSk7rk1w8vOf7pV98(-JV;I|gML7vXEyzU={$IbAez z>#}0w!H0d95BBiAhK8T8`u8TnPiof#MXN9W@E(n@Kv5Y`lOhRou|mV^SrhoB*zwQ6 z)f_G?zI4=K12-j6K3jh_oo-MxKE~f1tUdq0pRq}6K;k_ro#paaRzDNwu#g?*QMo*4 zb~qa$Jl6I_$p82sTQiM0->lAXc2TJuFvwrEW;pukuQ1Pz?JUKbtcJf6dQXc#N>=Le zIr`rVp6hDY$j#R)UCr;Iyp#*?YvvM_FI)5(G9CvUn0=hpwpg;#>e415HB83r4f6Us z|B5GnmMXn39vJ#PA|d{bq=BL27vWCT_&Oc~Z-ejJpB{!ZBuuh?r>Knm-asDm^0zK2Q{RK(EPwn8>u#28!AB{&lxG6g#&u4DG*+Mg z8+l_e%>_QX9?>;)`s7QU>Vjozzbp=x#_i&$O3EuPyyV==W68ml@F?(<3A5gEgfN9+ zl}-=A_I&XC;;4vsck10>aB*Y+Ev~GNV?zPjX8ME|E#{}vEbp(>fvEjZ!83x+EyBa} zrX;@V!OQi)Z5JLs;{#~$tKvr*MJd-y4!$oXQA);^Gxk zqrmBsOnDQ;r%Yz2*!+EzCR!504haz)kps(hQn-xC4(V=rWv zzq+&0y_T*nphZ562Mq}?Jm|bXSYURb3VE!dLUE-{^Y8{)w|}_c0ok;blcAZ}cJ4zw z(*kd&5QLr-E$I}1unR`Z<=!3z-2~E|?HGqKEp7u&H>yfN-T8bsAgH;yZADsFDs}mX z_qBg~`F`8}iNcZXUqmE{{RdE3Q21&y4-&nx4M4n(WHRk!ivRA@aEmcOqlD)M@O|_l0hwUnah8>>fnbZ14%k!zX0PvRskkMI$RD zzmD;@XiqlOSd5F-QSM&{kzEP@-CJ(<9KY>@7n;9XZ}!Pqz4J}fWElf(h$wy_d$c*4 zCAfHBJ4LqTy1nDp^1`p!Hs9bM1@Ldme*f|~ca(x(N}RJ1zlrbdGNBx9v;K4)_O3rM zRg$v6s`yaOxM#_74@LJ83pH?pceo0ekN_l#yCiV3C(or3&}U6`d!Wz`QOfe-9qK6f5~TS(t%z4# zuD~#seX`mTYIvX~FcsWxb@lIpug|#3 zOSbrlbh!=a1njS$D4%%E&o-{>*DkDvPrt^GNOg|^VMTUo`bSGWZ5NA=`UWzWW@`(i zeJ*QyX*lkP?k~m}fY&-+j2D{=sCQh{RV&D;qvRk2i*7VN*J2dNU^|#5uEHUCSddOY z>WZ#%$d?XvgjyOqVC8Q4*$qD@_NMPjPP*W853W5!n&90HR*-*2g;#xjPXyggcKch! zxa<~^yBHLi#(AlB?!yfvFd8T3$;8_%C7bh`Opb4kE)u<+BiWx( zfp4-035{F$cNCj0$f-mNO%-$!`v~LvY|c9EJDd@X=Rat9%IQU0FoOzS2kaeZ$0 zsnt=YCNMjH9xd*yp#)Qk(%mp~^2i2<=xOlxI8cIz0Yed{s$%HDbhnJ1%N0FT(;aG$ zBiKO}jU15qKU#-e7o)(Xpm2Y`d1f;?IqRNo6<%>})z&lLbQ!y!ekN-AhGPZQ5ivOD zIeNFnrRnzicA3g{8dADErhtlX-}Q5so=H27MvQ1tlZ}}RS&n|Bu232i=nWoPgfs8f zwIn+?*hH(!NL2j6?jCegL1ER(rY|$*(;;CR;nZm(=6`Vb2Dyo7{w!cP4Y>)C--XkO zQ*N(GP4?jN32m^_JRyvEw;efEQ01jK&#yfAw+3KU8Tf;<(0+sz)m#hr2Z;%{sfb-k zQ&YQqG4SI{A35yo6XO^OI6YJv>1zgcUni~u?uJM@2uGkU|ygc%}8!SP`FQG z*2adI!sG~xGhSF0YG&;`o*C>vsfVhFK=ltDzdn5Y& zd^KvFYHN~nEj2^l+UaBHD&3}iX$sFC3kqn9J+)kocMN1G398h z=+KZ)61GX)ZH=CPN2HM)+ut-&oLF5+r$os@Dpon5KiVK%m_Ll2fYdn}IN!3IwJTX;{djpi>JhE^6e?J6O424~_8Wsc?* zj!`f@ONTRqbVN~BIghg*fpW-38BWf^OwZ>W-_f$5S;lX=t~-0qm{jd((1WHqQ~z_2 z;!*zDGwbbc>HAspsd95&&TDf3#qM5(v#0jo3(8!+ z@6(&@PR2n;VXtPk$h;2uZ`|K^DKMG)n?@N07n#ru5YtbRT*;EWU}no_C&l~+**)pB zHNRniA)em@aR+2i6W=fk@FRJwqI`^G0WLQ=`H`aWx3q7>1D*l~$vz~$d9d*h@MHnh zDRgWU4sh{V2d=h^WPkbot~G!Ykko&Db%FP`x-HoQi*=}la6{;lJ;`{CK!mmC@Ur?9 zwX8c3Yg5wt%R#Q=)aP$4 z%a5~@DIUD!IK8#=iWuTSCcpS>HC|%h{x%;?NC26{;2$B%bt4JCWY30sX9Xf|HHhU* z|1KiHaf}@zaj=Ghs~jEefGdfAohp_hm?CPXX~mJtf+v~ zda!|n7wv9{+DvHJgroAIlv&M>&*31eX(XQmjtp_yji_N83~JuyVR;a21W zSVuLcy;cL zfDhJ0@8i=CuZ-p|<|?WYG>=1xu@GeC$Dt2cfbLrEye{mEnZM@-1I#(9mL?}QW^0ov zXjyS-VB>eh-eNUpB}9i`{+Y>o;MN1Vi*Y-TGqq*?%WymM2N#v9{@Jxp)i_2yIkNLF zuYI2WO65kB7IBK2iITF|v!BH3ov=!B!I$5T*(JBpH)fl!JA=1)6EGO>{{=i>-ITa> z_}upWLfc;LA2litmw+F8%Oh$$zs2N5PZj^!B*oFod!2SJ+Cu-@;y-xk?;E7JD4OfTnJaHQ)F3beuF55<{KVp7 z8mG^WQ?Hd1#8ICoYg}F_127V*vZ!MTrzoQnzzN^HqEj3t%Z1qQHh=Nc-KyIa%?LH1 zreu4K%^*G&B3mdRyHQE`^Jj?veB$Eoe6wdo=*X2}k*wy?Oc$g1>A}oMU7Z=M+)T2~9CPbJF>mOaAoL9HaB_ zlPJPb)3KA6@QhTUf5fh#OY|mM23IH{o4>%Wj&i!t!kA{?oQ?wS6fobopG`k<3$zx_ zd@eRuYwT(3G*YlrnsiJ1M-~G#bUR>m1+CT^c(af5sT96`hs_*!i{NNQcN^|}67p9~ z2zdkf-$|w%$C#{P@C?V5c9gJiQd&|uuQObg!;-X++nXN~LcU~u@aZorqQ@$t0rL?@JpeyR)bbLO{8rJ(EP@Dp~tDn9G=eZRaX zeeJaO5~_lqKIh^L&LjM6O&6ay8tK>ZZ_%tWe*{aZm|~}L*x3Dx!w6UAU2Gc@=RSq+ z?&_**mY{JM`Xl{{T7;6Or(8LogRXjwWz5x!DGImyV+C#K_{(Ef5VOBNYN5o+znR1f zBfa(h6;J;=Yii9iucGF6EUVB}cWN{tXK-{pzz`rfqDHeVKb&3c2Bn^948gJkM;=&C z@Rk9~lCgtN#Ei1H-O_bHd^gr8GUhx?E7xjr-N9HfLIuLD+vEQG&ZC}L3N3+9#de&9 zn1ShnYt|u9`d(b8xz-k8y>(`>FxKGO&5ql&BJTIPHIw z0Nb4i)3=}3stQCiV^LA=ZUu=ORYCH z$VO7#)}@Ma;cq~K`5K+{qcPsY`vYa=7ndDy9W2&;h2NKSKZ9x|p zEN;Oc?}`1O`10QpAo*Z4?qt0nP9B#_XZ!0o%`V%`AY$@CmTdg-EHY?X^ImVp3*X>P zb;~b;gJEHXk2rGKYG@!JA7!$*c9vGP%)=d@A^zqTQOO&5e4XqkBN_W$#8vY_SeA>L z6%XVuP`v@<>qi%Dvs-my`u5@%hi4J%(T(Ths_cr--?z2(su~1uoj}j*742 zvoB{0L{1>?2juqe)ee*_zv8WrCxBm}VE`{{EwFhG>D>!`69VG z^}wR4(*G?I-DrpKN{JdtufC1AFlCcGtz&OY-8$Z;&yqX6n>ZBmLJn0jtLrje0Lw;c#o!K3;JWMcN4f5P`=`tN>1TPg zThmZkGT=l=2t&GXiP}YP(E8$R1vF5HDcC+6cPz&NFr7B*I?GASP-%O ziFl>EdzD`;b?Bj=W)T^?TOxFHa57@}8|E^`#IFFEhf474q7#G1ov@fNp)8Ayta5J# z`NBW2zJ_^*gVgFEtlH!eI7+q<>r_2Xn5T8bpIT(qytKp~+?sE2@b7-IyR=TI=T9nU z@p&&`W8nP(R^RKtU8d&AT5U%N_M$y!7coavjoOxQZH|`^a5ELoG3`u_NWn+T3IgcZ@zbL;RhAg+2- zzXWO;7*dlEq6m#}^cOS1R>V*TqRlv_i`(KO%4>&NzDow%f7h_yaqp}asN1zLhn<6E z_$+x#YEj3J2sbcOZ1(!4BZXzka3`;-3d28gMCSjj^XwcnDPM-+oSF43PawtFo)Lj7 zbzUDT|9$F{?z@}U#*YJIim#6SMeT(r-JlT|{FHXaj;Ry&OPqOqyQ^bJL&Q9DsIq30 zOP!Ykt7{vzIKjxDOsuLh*1GXSjGmL9SWHXX4-aR9cgizLvXyvg7JlawM$hISTyq^d zc?g{ZO>u2>scYQk)Zg?F#)Z}~O_AMZx%klpM63>>DUNGWy0Gow(*$*Y^T5H5uCwFM zPnma$=6=W)JuBvsd!kYvQPDWx_0B7 zRIXdcU2G{obBCrapz4DzlSK$q&n|P+Mmo${`|a9w5Qr&Q%cuF0JC!NtXZ1$n$D&yn z*EE{(P2-7{#>@N<_nu7ucP&66C;Lr8h)-CsPU(|s)4`Yeq*S`)ht%w@>qyJ8!W9qO zwIW`b5=HI@X>IH7IXc+q{x2kGHx94&pV_5J_~1)%Lo8FXqvhp;?;9H$N)ZTMhSe&^ zY8Kb60SfZxjpongTsqs&V}qu=!x=u~8%}pd?m6q)l%%srPoYQG_zu&7Vk5%PR;k?c z2#8}?%pE}^%zE*@_zk`|T+LzB)}nFl808+p*_znf`>lvW8#*!$m}{YN{iCCzsaXN^ zqt=9v@CX=Tpo%rfgW5ypi3-w#Esw9yuAuDJZ{*UZuK8>ThyHmJCWj^Hd$E7^Iz#DA zRTQ_2e~4KJ>t=N*H;S=Qoo=@mzq!Iu>Kjg0pwSh@zr+aWOywVgzr6IF>=UqGH!EX$ zk~tM!lpUlycF}}=M_p;RgM+oc zT||<|{-Dn`<=9sn5n?0;KJ(TF;Kj^6TCij_;B=H4qL!Vw)TOYHcd7H$o6|KifGgTP zTSAf2LNi2C@oBc);EfU2tcFaW@n}NbK-h`Uw0X|;tWA%XM;s0cy9)N8? zcqtQjpw?H5yHsIoO9xcE{DlpyPVc;Ubux9vhx*yn1EZh8fPvW1Z85o%% zy}7z-jPs>K4xwN{zwbc9XoBD^*E;iOV=mTVnGAMN^5Y%Hzjg)AzG?-Z&=U`3KH&;VswREq6vm)wgXj5{CB&_lPNI#9F$$Fm zY7Qdug~3ftt&fjtEc|iO&pKe*3dGiWp^2qF6T6-Yr3UyvYxo3p&$@ekj+%ZCdg%sFw{tiuc&- zY}P*-F$z3;5Sooz3>WcO^UN7@1D7f@uFEi)V$9B;$+?fx%buHhTHLMLR>zOg#>xxq z5R1S_Ed0n+Z93L5PE3S~WAa`O{LS@g$jiV@iQ@ZCv7ww-%3|s%TR+YPq~g6p-@q<{ z3s~#HsXUj}v>U_Rc$CZn5kPR6TSEhL zoBiYL0MgZeBImlX13OOtNA33iFGLd#ync>VKca3tfr;UN$ILq`jH0)G$A_%FpftS;*^n79QU`+99d2n_|a2dK}aC7*+M=H*$nPob$~J)cBH9(^Pe{ z=ut(9d&Ns)27@?YjqufpgM3Y;8|Y_UNox7ejC6^Z_e*9}nm-cByO^O4xV0k#}9(!pW ze5#x#)BM^YJgseGy5ea6*Oq5EUfkRuAb~`1tRG)jExx#v8_Egu9rL2CTN|11^qwor zn6CCb;AYXb6EG>9=?De>Cov;rE~zTu@$c#&l7=$iO)dA}-(hVX>)7#$_j7*s4>s?B zM^+kqSY)4ZKM^tA8WfjIMTy-{?r2pqb?R*Q#RNKXfeljNz{?PxMlWxk(a8eG;Mbmw zaGFs4GtA0u52?O;Q;mH* zH4jh?6=T^0gNn_YsO6)>>7m;O-b0oSp4@nCecx#JwIwL!h-cZzf*nB~V`w_7&t{;S zfg|TXFcd9yRIUo>p?;C+)7TKUX~ePNq3fCEw^h7i0;?&u@-)uii89S|V0k_8l9M>M8_}7rOd?!5~?Xo!$!OKf;Hj$g&D6cUxzLsilns`rNbq zfL3_keW;iXIwX0q0Uv?cWSkIw_D*2KLycex10QY5q2~}v>lLM-l`cKg@w+quUAQQ_ zXuB9!MG|vfky??`^=5y#?Sp;5t9I`YaYY8Jo9FvG@2(UX2Pw-*JI&8VSim@$Zb3nT zb6gJ#or}GFe@Lt4Q-LVlmbWSQY2S;#B!f7x|50I&aca#NP!kdOQ2AsQpf+iXCvfv zogj^;Z2sAv2ajmSfe@p58rPd#H>m2WS>ks%70$kc4f%G-yeHQcu9g+dWZZu+-1i;5 zYG7deIrjt&xePuk;An04aUr``Cczj3k%6!nMBeWiorZ8%-ud1~Og{};W$x<~+)V@h zsmXpa3`4R4o#2g^l3w6`wU5{V4VJ>kMCcIjkM2AwiA&FedH4RZxtV7qz?SaMON6YNJ0KNOVw+wJNU4J&XGDWy$4E1XHFKXDXM! zM+xtGkunr^j;jd=^u!ut+`6L1XLzNx%xTHiKg-no>FGMwRLh>OFGkc)+8jX3_A*kk zy>{fCec6hwX+EQ>YXi}0_a>saKEqPJo?x&W&5XOng7~#?hgNn8wyJIOWsK%C8Ohf% zd^to?bf!lLT-5IeS-zl=o|nthxc_MHWK`+fqrrF1E`9&^_?DK~9Q`9gTsm49RF>|f zJvLVnBwO1=t6Eq#WLzu-7K3E>*aX6tnzX2!o58td`eA>aoYQx6sVDa>FoyTWt#U03 zD$7uzhBH9~Z|c$x)Zi^b84RvGFMji;X9LgNYfpfLD z@JuLbmXW&AI5kOTW?^&XYV@1QAUGTtx3u@|{k?Gpj)cn4xz@LDhP7K(ohvZnF!rB- zPsMVkMd`CSR1o+X3^tVG9D`n!Yv>0)L$9t zU+7L&+N=D{{uKCJYt~rf?~5-)P7xMf`FmReM#d48RhC%qIKPXC$xrxD+d~0uUE31E zMSLhV!Et9N0a|7nQk-}5;bCLhZ){$tmgBg18Y6FC4@jEFnr3qUF>4>IQd;@jvr>{Hq$g*|Sc+7UZ3P<{9B#E{( zTulKe3_<$MFCI5O?|KgodtagcCc{0uYjQ6A{RGOG&{*1Dr_#d`%F`91S~dl*RO)K< zEVrC0oc1(lM&uhJ>x%-cx=GiU_tvb?>@h{E{N?ctadJXOj+!W1tg$Nf)xHJJQRcBWUT=JVtJ z!)ndM?+(|gK6J=?0&Kp(+wjf$&Re-RroC8!hGafQ+t!}z0J$5AYV3-#2aBmbD-<7> zvIb!EfY|u#_EuFEfGin@tT!vL3nG-QPY>zlP4IxwTMa{liD0`B5Ck~5NVg2OyhsPS zDDpmhPy^nYu6n_~N9C&4?h>%f;*g6wga>#V*)}V8=g6-_|v6`uPp3e^!u}?Qqltr zek$ONciD&#Z-JBaro3RE4u(1RAdZ%fuM@QG4&_H;iX6mb8y6l42x_bOh*nXQ7$xkJ zlaSmVVn6q8;cS~bLy|qS!0cwc(Crvq@wv3U!V010<*~qQu zCTq1S#oDS(67}dmZ;?Ph=$#eC*#xu*<(w3*9|`#OOC;FeBvyF#xIGJTQv-e07N-26 z9QU&Ty)_v;C{^qly~BpF-P~bTwc_N10h9N-t=VcDBD>y0wYzCRrMdQnm|B;(FrAMS z>0j6#XpKHRoKsSFefW<%S+s9H(~7t6=#z=lN5B0Ra}l{X)`=M*56MrqGp(C7Of9yv zaLNJc+6m+O7~o*(!i<*g(l?d*P`=r#EPo;L20`Ax>7kORIivfW=Il=&DD2?|92yv1 zKbPz^?n^WAM=MA2XY2o-4^akbsDR6qN$Si(sn{IJVzuCt7Vs_5POtaY{j_vf%|7qc zPcj~f{a(1oY-|%Rc2gQ92v|HL|K$V9Ky*l~TC=HC@w2}WBiPPZ{jSfCV}%C+GwEUZ zk6BJczgTiMH)H>op8QVde0NQAuux+VqY|NPIxqUJ*uzVLmTOX!&UmZJbLQ4Ve8(Ho zOaY@bH5Hwi&W)MZL{CoS|D9)Jb^v=%e7g9oJ(7rtiTT64!R`^u>*s$lB{2%sc8QaQ znS2%;uS95PV7$FVD`0RCGihDN zQurrdIK1iuJ)NmT+xlSwr=2|^#Ly$m(9%BFA(h{uL2XRq6S=HOE3r!u0s zXWU^zeNX2cyj1WI5G*iX5WVR=kDd$M^d_x2JDl~d_E>yHRfr4yw~!!?NryJPnJ61t zt%V4VW;^B}OX^KH_zwC9l8Wcyo;GmeqDDwD(q%65yXQ*myRriBFljP5kC%|<3#mqO zGbsN>Vf}k}M2(+?B`FKTd$8;oxs{GGd>nxwaiF_|2jlb(^!Mp}c8+mAbzboF`WgcA zIy9daKfJcu?8qdx7eBV9!ohVwF~8}@$R&AZ%@&?tw{i_V-xJ+^Azf$LdA)q&P392L zy&U?VI#z*E#}I+a-w3@{!|+IW%G7@jkYnuAQ#O4=nGX`Dx2+r*#u*Xwx;Tc^A~agR zY~RI|wtutD%i|$r(_ksmf1~I4rm+tFXOew@s|V-%$&*>ZCKWIw=w={@Hv+6YY`L|sy`af@f-ergZaGUo67;~i16ctZrvX~Ipvse`C<$-& zlK_JN%ni2;4#h#PU8`Y*=~k>sX-CHYKHjuQPr;TWxPQzW6NiT8J1A-qr{@!adS{y)AEOzOY0J{Sm(HNU&6mgrJXhic498G$$ zuJ*EZO;VPg(vtzLuy~fc(M){joZxgZ=!J5R!;V@L_$J=#9*~H85|BXceNXq}vB%~N zy_)Hp^VcT*%!E7F3-r{@O`?wr%0Opza#yE$165WlK9`FggNx*?KKnfm{sW@Icyk{H znttxh-4_iZn&z6RZYz5?H!inoUU-3-FZSKCp4hK9!D%g^bsdxvt})CN;WFV#vpah6 zZjpgMlv_^@I0KG-B@r}kj;l!#kOH@-W2@8>K9XxakqzhQ$FK4b1R^aGSc&DsR1$@2 z=FcAQ01M1Rle?7`%@Y=hh$1lKsJ0z4?A41-->!6So(!nzgxss`)z5UIA|jT6J#~_# zaP*6wvDCG6VJn3b+W{yp@?%zF$-b^?x4?a5w4n3O@}J)KR8X(txz3%T5s9Pn0{k$& z{R5;%@BA}}#KhiJsnM+Ym_B}_H1X&BTIO*Nt{tHRw=K7!Z>o~?KetlsYh{JtzM-#x zxFx~e9AZx$=6CzFO@C};fS9H7;{CqR;p)^J5E+cw=0sow0LER{z(h@n+-T zRcia(cXQnQpOrm9=9a#RAtIqji=YKZyT;jK%Bp%7^~(!;&B!u+LlGQ4)1cL{&2mIY z$1V{wsj@81A+5GKc=Qy{x)7mDqjyXg@%RX_kS<0^L8$|A3G-@bNOujs+ubF4JE;%x z*iLewmc23d5NEjJ7#?)l^?Z~!$Fuime4%{F`pn;`Nw4-cBo}?us~_kq?U7#iTv2( zyX&wBH*UJ9v3G{-5<&@WI(KD#y;A2$OC2;#WDtmtw)QYBH=UH2=T`v{8fJfesI;Ml z6SHNFkQ}7{$8=O_PRFIl+r(I-!s(ad*)FgA@6`sh3aV*{xEo4no?%$-+0+HZKb4s1 zXsG6^y{+X1PA+DXJ|`AMC1qVNxd`9sg116UTGl(tN?j@RNF02!1W`k$dfAlp=wir` zL7A!U#|M;~UE!0$>ROYQ{I6SAjAF&=JN03_{@3va&V4Ed$3Lm6&=a*b56DbZ_CT5L zgRB7CK@(W9F-tpn%R#++T#c>7w8F(WI=Wi&XWzBX*OuqX#BiE5+vBJN-DUQ}Y)zhc zV_sc+9pkKP%gh2~7tmrevm}m}YThEPpzum4g(BVl`Ih9zuTuGyTSMSY>Bg4rPkF;e zpP@;`NrSKQ);Y8f(@0stbSF<_!KOAy0@;--Gi{a2(Em^U3S%c`G(E`(9kC zsK#;>_t+w9!<181L{ncN8faEo?Vc@?A+Sa5d)J-{ov0Q!a_kCcCFU=l)-6gX#o^<_ zB{|&Hu4|sskK>!x1`F0rvX)KIYt?f2n;b$gYT8iDx;VJB0?4f%@V{?&JZ1{IvNds}9~^7?vzu@$|Q z8%W+BX_n^?=s!f8_=cs|RuyxPvY3>2NHqm)ggrVCwOWzvGBv85Aidf`h$j0Pnk?kV znS4}f5f|_!qsLt?X5G=eZYXC(5yBcga_;gB!5ZTwu*xVO3o~S#-U3RW&gg|sTdo_p zjB-FlB26D&*#Nh99F1^0BNq@fHE^b~pcZGEXLa%N$P=4*Ul ze&_J&`>och6sOw5JL=xeC)ZdfqFFscP65v(AGbYv_XwXcYrfNw9(!2^q&~|Tc6#vUyVC)C15U_F zh0}d7xv}Gfa)l(w>tMQ~gMt|NFCbvMqe|a2&2k3kt|Nx99Q#qnc({a(De&#-oPg9}y=woz*a5Ro!7au#I;^U)5Ab!22=h)bWP0A&YAx7RTd21;He4;WTs)WEOu2_uE&wJ%j#{O&VG!8IKhS}LSJ!`eFnC3@#~KM;yW;I`gg1bd3wj_yi)y0u?*otCKf zY#Tu|fcB#ca3de)H_KPvkEX}l>3?7!&TYPR7m8Zvmt6eWAzbHP01A&@cA}XE)r)MV z3B5C#oFSF&`jqc&bn}B&y&(36Mr?(eyKd-oJxvSc-~z2#^G)cQUNMhupb;afu+K@s zEw3@Jgs0QdPPjB)3SE7mM4?68_J2eqbB7WcK0d*e{|nh%)45nsI}K6QJDN%;ej~GU z7$c_h9s64h3U%N6QQh+-ENGWj4_aORZ~C7fC9h|5^+Duc(SvHy2x^znQ*be1`M5q) z%=ux(<3gy4`zZ3P&S;q=z|({7pn7W8_9iQ)ntA1xcq}u5$9#I&BmrI;S|t`UH1?4y zqdXNml4(T7oNMNvd1;HhJ2fIn`H%RI_v`By0<)ObYyM~LD(y`Q$r$5Cg&0AUPBZDa#>r)cgF92QQZ1x0NAWvu42SDL}|S7RzwS>&g=ZT3^WBb&X=M$$uqqLL#0g^~ljYIiyI6R%XH1NT#Vq^Vje z&a9mS-EzI-8;DCnz`fm@1DevojLrXi_q$ofCbv3-ZgyjvfwyV4Gol%)=_Uz>_M|OYcm&+KJ5&IY1O()K?P;uf-1FV(VCZn>-o#4TAW3}N??>zKT%b@seB7Hk|$3;J^_qp$eKZp`d65W~NJW)#iCza&OH?C4vMKFpIJ z35s#7`U-FmW>Grv$HnUxV!Mn?{j$iM493(6LNBQKYxs(akY$c0#frbCSoMqwGHMu* zbGHDlD#577+R#3e1;$pcb@)P>*6-ykSP+P{jK_Lg*TTH@u6m{S#*8~PJl7~c-SmT-dsnQ$q1RI#paGFO7*ZGz-; zt2@8(f$wag&d-___=V{8_E7bE8ouQw)epv)axK&tLbyEN*eHHO_X&Mxy=*KZt|M8t z>xLF=zpaG~F^ko(3=d^8hANc#kQpQR;VDS7Yu#W{y@le0eg?j{5Ylg3Pib_Kj z9Xa3NYJG(u9|(MS&w#xIS&(bka>{uP|Ab2(n9$ZfL;@#cn;3d7%F8#B(=b8I(o7I>#n!&J$2xW$Q!}cZ#l2T9lkr(|yNdRNOQ@9q+ zcTk$jBlqvXnR3xr^9boz^Fb7}?>@Z6uj@gypRMULF{~3(1O1+cx(k&@RtCP!uy{Ti zbQKr&u)U{mT9H7L@JX*2SXln1!(cxz(b##f%Zv#}5|mJJzpLBo{Ek3LusyjH58bXA zg%045q;vcY-3j>k{r=Fs)x{Io8erHalRt=cHl5+M%d+MAViZ@qg92B_9w2T?o%Or= zIKWgnUKTfi?uNT7v8YjR(hL|HOj#b`1)!|8ompKq6AQJV(ekdp2=|Qi+DjE zt!gB?<@m5a?<4kj>;oDG%3m*F83XgmOV?;sKM4@EVGp)z5-;QSc8n9N<21?8p>wED zJES9O+GB_x%P(a`M$s0lo#q??mfn(&%C??K(v~Or$t9y%`cLwKpo96wxl=|5_!G~O z95$yw+fFI}i|;PV$!PNo;v4P}yb5aT%P#~+ zvvZ##lRIc!vIeEj=qE;;#bVLTSv)h5xT_3OWtQ~9RZjF3VILC5-M~0X zN-lE?CA8S4@(Yvj zZRoP+1b&-vKIUu1-*_ZM{JV~{agM#T`Q%+cWL{<{BDOWV_X8|CE^}cpGXjxt@jl2L z@JpCGP0r#{4 zGK(~%(o8IqIpCw&wcgeUE0guLYi1p+j2ySt_!Xuw*(8J?pVDnoyVhmkdB4zX11oaT z@m8K%80RSrG#;pJm1n#+BRs#b$|{z*Kd@89nVVxI;u3xWfpU+I6+NJgap$DNQzvQL zfZhD(yhI=JvE6O89~0MdP|@^K9o8Fmq`N~3eZxZLYOJcx?Tb5f2>F)|P@Pm()9}R* zjdMQxNmHuNJtaYS0+%9I)5!UQ09sV2%o`Amud4sZX*r^K0H=|qzpr2Svos9RprqR8 zXe>RmW=qfVe!&QIVMY_5nF*n5Q1(`?bYU;4Jjmfgwx6auD!-gs+|RgocrLz z93~I{+?xDE<)i&*PkXBS=8GNWM4MYY~%h_rZJKUP9a((8Y`*&Q;dhuG!E&& zCCFM@X;^Famm14`lSsVNqQOSGe?fxps;bdl5mL&|MJ-8t%j+FzF@i`m8=OPy}EXb#?HS)3QHUgT4`D|A?RHuc+&1lP>P7Rl({r z)No%)*s#()M?I*bG^F#{tMd7{CP`-6=MfE9_SZaCFS&%(9K1M65jB>+1hofe-@D3G z*NuWB^{gTpajIp@4a3we+5APUgK3`a)gm!-a$0%+E3~;| zgq70hSabxyQgG&Z=X+DUjqIBnZ)Q1bAB=@2G$3=B48ne!q}^zNWI4ksbqC1v;_%7M zt5FX1F7E<06|fmn7b;RfDwtb{{~3F7hn^w9A6^zZiT!H)rIoH$mZ8dnv64VxL%%pS zt2ak$)R`+4yrMymVwfdl$+ca}&NBz(1rOHMS}fj;@dLy6bS)GzV_~a);F3M?#;!4V zfmCM*2E5iaTx62L!_+yDdH-Ft=hH@iFf~p_TF5jbChiUBm6c z$ORZ{q~MsN=6Ip0Y)*=9?Y0Z#5NRo10ruVc4n^*eLr&!J!>d z_beL&&zC4SoAopNpA3RDJ;*%TUYb5?d$cFAiW$^}bZ*TDdFYJ+cY0GVU;6u;0C1i@ zTDktizUqlm`NS-)-Vwx0+q))w%@dw@WrBHQXne37fpg`~pbx-GfMo!E{x2*TKwTO8 zoP8P~yY%njk_O&BOR$W!Zq6YVFl#AstB>ms2qu=eD-W{CydJdtL?OwOzx5n9tU;dE zvs3>lTEa2PJiq;OMNflsn^YUcgk444+6=~y(z@-+Xp;8TG!J(f6ai!bT1rX|_f5Fi z0<}R&@5RWQ1H-F;lEhIx*Hf(z(5*o%wZ=FFudG+7pVa2{AI0^6*%G5ff(prcYtbS6 z=j@=dXT?(N550*joqDT(^#FmL48+4Mscx7?=)za6Q_(J_q`m>(#NStGCmciz<)~48 zj6?t;^)PJ4sQ}OQ4h&1nwoEL!EhQenkQLGLxO4TMAQwc0wJGR6lKn)Op=m^+$ARrK z6G9Eb4-AnMyP=rsrMe#@O_G<`&_9mw6yH9hy~5dk7QvZ&zD#FrMSjB<6}5MFXr}Tb zVlvqJCRa)xelnpMn{Gi1*=#;A!)(27kz&Bjc5}R4wk#dh){C=SEvf_$=8KlE|IElY z1=AuV{>4~S>NWzTm?K1fR9g#(Y5W^;0G85h4Suzw1};3L1pP{WDvqGF<}@V!Ei}p>mpnmkA?*%nOu(R>%Dji7G~o_RMQsVnsQjCXBy=;)I<$(XrcqG1HO0+s{(==`DQ+4we5EME_sU;x{xwmvZ`_zY(;A?je(! z6qAzX1^hLaFs^A>%Z(1Em!)XV0TfYbus|~lFIh00Bqb2Ce3o+{V^eBd3ABmzGVJId zV0ScysE%Q&r1KA`+;=>;%W_Z$iTUcNX6EhaPCIzw&LJTd&&B8Gj&fV)hD92Ar;#Nq z8Buc5zLdL%W2Wu}Aq~px4^JH{pdUSYX>6CWhgNR+CM(VfAq}XMs2a4NoEV`DC4t=- zCZJZ!xh#2G7zF+3Kk&mVHDq$`U7_QBfHdK~{ecK|pn7BmikA66C4G0bZlOI271dzq zMZIipo}c=z>k-#_*>a~BJf(3tNrb8ar1Sb=2GbujE`SEHFwbZ$?6a;#iKt+)X4tG z+PD5YL#)EL&K!dOUJdD2NS_T0sZq!(#Wk0!>xU(v;x^>n_6Jq!=cZ$=zxL z45?oIyZ4L7$CFee;yG|5K$hi>!<5T6%GO zR9YTl_y>j#Hbd2|IE)SUV(IL>hx=r-uYw`eZ7?iE0{U{qDBFr})y7<^v$of%Zf z885^uLG@NLTl_TRb^1+~G)`f9bVYYhHoh*gcZyUbDKd}?M&Y@;Vq?^c5LoP9jS1>Dd zBEoCp#TNO)FL4Z91Y0=ye?SozepV^#Kimb^E1a_y@1>Z5XIpkTi;rNmxaeI)_K|TS zY<}KCFO{~xqW?mESY(t<&t_GrwVe8a<3qvvWSUHn&3Imzhn@P~l(vD8cy*aQ(zn)r ztkvj3|2hT&HJlt`y(-Y&$V|yaM|QED|Nb)M=;}Y6UEwZwG?O zMu;tdN&vcCd0liadlp_4foTWrD7GNTaYgc*byfh~GAU&7Jt@gYxtGTT^r7(>(hyfY zTJ(AdP?&|g0dW5qiKLiN2U_aQ1BU~gm6N+59Dv7SMQl%lz22*kJjKq+R_*LcA=<{h z!Xm0P!~Stj1RdgMO`w|7)ICq~|tr^Ku z(!U&ytT9~>f#U*w8r=?@)rmi1qJth-G(ZF8`mWO`*D5aPYw9}O@<)eGTtYZ?i@mZ%933>3Y@! z0k}JKaXnDI zE8wYhDvy-cw}envTB(S^4si$pTLUBI+$}76IeCx&8y+s7AzU}dO))k7%ygzscHW|) z>9ePS=s>JbTJXzFs9ub|oGFo|n43pq#Lw!G&0(p%W7m1WG{To zAXeb(kqX75sp3@=R%%KQz1+z&x?MnP(JWa%GePDr3wbS7y;kvDvYvHXt|Lkziavib z#^k)TxO*XQh9PskuoFVum(yDvp^}-5BJK^|L9z>_2W6>?Jx=8i)_(@G=PBtRy2zcv zJQ|Tsyx^W!1n6UPovruH7}~>Ayv3xo+I05w$X??DuW|E36Oqe^H7Ir|`mndICJ4X) zGiT-%kFfZdIAiYl|Tp zULq?rpYR6LWwkO$Kv)%FmFqHk(M-8RSsCaVyGc4&D>bN%ds2CZPyJyz=)Hi5+S%!5 zQC_|VW5Uq_P0s8j_jcQiqcaZYl!DAtcZ30LgL^6m5zC}K+-k5GUKXw5e zFjtou3Zguig_X|w+3oW$q>gUcL#GI>Tpov#r%uiZ?KgF-YG>E_e)NT3T8>YR7dUF^ z`3}httvXTL9BP=P216Od5=xbf4gihf(4>q54$MJ>77wjDsd^L^n;Rh1}B5a&s|P!iKI(k_5%81U38Qjqtu` zRnUxCi&MTIuZ&NMDQU`P>NhO^r1D1!>89uHK41KIlzei=t1M-=*7~riINs1BSraj$ zdy%FTm*f&LjyHm=x{_wH;Ly^%&@}StDrwk0HFTX}KAOy%LhjrZhk;#(d*W+tD^AIV zG`?#5Io+DgVzK;FxwXM+ZXZ2Po{_V^k;rDb0qvK#lpAW@*5PPG6O}Zbs;2wys2F&S zF)vI`4`SoTi~5&V>ay$hbBma?NLz;`zD44gSMUqg-^@~xyhzQZ&|2eN`z@G$9{qAi zn9*3FqK&(8L{C58l7)p&zK9~ z@a#R$dt+j;Vf1HuQYlXCAFGiElGVr&IYjg|pLCOzpJR1CfTfn;_fvtkRKVGGDn&9& zslzL3&{gHQCLgmz4^BW4?6f4YwMIIeCLE8Suc+!xp{Z}Eo_i_h52nRYg{WFt!fHbm z{^G@2eJEcJ-Xk0i`^-C)W|%c#Gg$lZ$O+|CLYRx+Sd^zXiJUSE+|o^N#n{?YVWz5}m!ZM--}#069m`0jV_!!P`7bX>AjhFbWM@rD##Log1i zcRMa9PsxT5gV-D6+6&`0*CPBX!6foyqzGGccY`Y5Bd>HOlZ}ulm=aDJnD$+ntxB2V z5rGJc313z}pA4)HGTONc-_bH{-Y}xnkxAZZ`J>MVv031q+eNCt3>Iuo8nv4rOH0NYkQOjKts<0&A?bt1$J9gz9qTv~us$&T@{bGezc^)!Ov(~C z0$%1jxyV>R`t}4((v@x#w9ccY?P(bfQ@N|fC8=X7Oxe4KHI+(tO_8%P5@n_SDZH}k zdego@iH8EAVY z1ur8MaDTj_aU^<*6#yJIjmLiaH|1ARq$JUBAXVFQR6fWaa60+~U(9v$Hgk(uFKB}j zfFC9VAOheIG(|^0tIeQ-)UEK5;d8S$m#??uvrA$cs^3Wo_?cgqND&jWV#$osM9F3Z zyhjC_gVxQ2LN{o20x@VaAVQZIK;*qEDbCe$m5s0m?V813PMb#xef=8;4q%w@+u^!H zX^3A}Y+Vu?0l)#`@NK;jhmj01B1KJ!?=0m2MfhHC=taKIY@{&ox0MUvIpA4TDD;&o zS9xd0Y~=Y(hR5m?%Zlx4D!a$(kLIH#4#Hci80}<4%2Bk(G5lC)AceIFfclcswBL72 zApC}*s@a`D8M81;`BQDKqJV4EPm<**(zS|dr4#tWj7d>U=nbuD{H@eO8|Mw)bu94` z`S%=RC$Zz7GEXr!PCLS5(B@ddV`kz*?8^k+$sln>@hZ0EsZ{O=bIKdBYc1SW?~PIZ zd9_30^JQaovP**dLUXULDM7y9GZA;TLoBS0i?($B>&#wgatV*ycF_PL$h_IXhDu^y z&_AZEAFeOf%#-Ei{n_Tsn!j>$9w5+bf^r^mf5z}2ZKB0(p(+nj8Wb**4d=zruH;e{ z%7l|}cZG0Bgx#i3+I0Vk866GXg>+F(wXChp5=#l!jC6Hr+7ciC*l7@K5!}~lN1Qba zyZzu>P(7_aF&d9xCiULEMUSBTv>wLRY2F;A6|o$pWK$e@M3&yQn?D;s$TU*lVU^bJ zwAO6-9BH5{!@n8ji%_q-4)$x(R(M=3y_7Jc)I&ZIC{YgWz402p?fh%Zq?QaT6TibE zayRnCjredlGVPb2C&x~P+l-H(kI8Wmq+Pzm3-W!aZkzdAJxE0NJ z#^rNc{*eKa7C#T*)VIIfG&#WSnzg(s+OenX5Xkh?7ku+j$b*R3qEB%QIp=ueKeJz|o+G#57cU)`kMr)$g?a4{JSJyP1WS40 zP5*zevv8XtMWRf-=;xCZD2n&I+6`jf69Dp{0jum1yA>lEz;j;w#d+BpAdY)VE2>e9 zsnR~ZxwM-fccHv=&jzCFVjk-&x;ZQV*>ydKQ{Z%JXND&yjwJmxwIX0xZcdJ*1}J7q zNU={nt{$q8nr=vOA8vMzy0pq-fIr+sy@&`+x#1n>&RW@&5}|dJtfl2W@4 zvw7{}lG^Pg4eJmNXe zUNphV;AhG71CR}5kB34Xa+@`)yp&OD%#l<(t#5In(JwEIFIiymn(e*N>6ES7l}DEb zkPc4W)72&Tqn*|z0P;hy~ZRxOM5FWbeRXW6$bcgBxuJ zI|@@@K9e$?440Dg)Ufze|7g4|6Ijx^XG$$vbAvRaV84l!HOVCdFKk%L=X2nxbE5TF zJHEDd`6p`^^0xyxpNeE>`jZ_%2iKncEWJ~o8kw;@!{Q9%a;omA^T-Cl-FJxi=Jn?r zoDX%*aYDN`&A0+VI zy-6h@PqiIUO#AA`u8L5L)Ie)DW>zQ=MKGnl&Yf;nQ_)hCt9d@o5t(Z>^eZ!OI!+H4 zt%ur7V${|bl&%+zhUxj0hv9U2u z2#tSKQmB4NF3qj_Az)4qkZv95H7%!nmc@7OpE;~ zDU*tIZUigY)3Q4#-wjGt{nk`sLtqb%bwKPwLb@7UtM!hN&?i^A=11{1{=FsMxUOel zXfeDA*?415K^!ctccvcZwh1@^*Hz8PEL5D_oVkkJH zwP9FFY?&5v_I`mZNf$gwVhBgyq`CZ#0W**;AGZmy!y8#Ba*zN>Zt)ywb54Vlt~8G{Hs&S>889W!yvbCky|-OxvvS|)+%3@aMOTpLr++egqNQf( zxW56;z|8=rG;@nB{X>=So}HMW;~9W$}oyf+F%wp3u~K!Ccy!o9(qo>cUj>^ zqaI=1wvA`|=n9Y>@L^p+Jb<2<64;mI)!)r)lD}8^hBm>qO*(&6Q+_toTdHyF0)sQ< zQ~$(n5q$RojOqmuw_PJL?+5i6K3mB92Kr5AItM}llKF2Ds3; zMh-qIqfKfg8rKu+(w#~Lk%v_0?3iKwgEWW1}cc}&JJ ze{SeT-AjYJ_iR?7T}x#PI{Qj%0I4}Q+DV9EC3+;-WK=vc+2|$n;=r&Ahu-!EJUUf~&AG4_k(RDkV9Ctty`T59Eh5=mI+mdt6Q{y;x3$8qzt8`5 z^YTYntlEn`AlRUPch0@6L@d(Rz4NUe^@oc9M4axMBx>*9C%IbA}W;^@oxAtG!tiPzjtM{hR5xwSka>nbpmBOMVVrM2)hJ|E?P1h zE_`;vlt}Ma)b=EZn(eKL_6j1yZTeatVmTqV*~OQK>4sIuVow^HHboANeNJ4&Id0YS zQFjH^WwO)e|7h~WO7J6O4@WV^p8pjyKYFRAAYOx7I1KBw5hE!jjkmRhD4eKFsuq)= zY8lGM7i`pzF%sukfM}MkflrFGV9?_V9i4bNoEzla!k^&?vh#B{p`T%?E8^Wu^`3xVXxe!-=7#Cx65LkD56g z8#^AKEUuPZqy$d#4%}Qf$;}JnoVfEOx9K|_0KeP9;xKj#9&TP1w%Fj*RsE}J`Io%I zAgCz#SHuWvK6r~&%q8O#k9^Mb5iXI(xzgm|_wCrdekLJEZ4=fkhlbAJ0b@0D=xvpyOEqA;;V8dELm&Bahdhan|>9Q@XA0OEwE*mEK6Vi zM+K#7sr4bnA1W?7o|b;oIC7SNA#s12M#UnhDPZKlBeq%&bmP^|_l2Yvknw~8KBb6hHioO&fF)56A62~iM)Q7;d zsqs$Do=}snXXK>KllCL{2iZl{Sg^O==2<15CZrXgmEKj6eR9qi|8)wdVNCGUN2#5- zrDi0rpjJUIHZiR%GqEO0Da$w|SjH^QE}RR!0^b>+|5YWy`2H2eH0gKRcf}2gWksqV)zM`7Q#y zIG|!SkjKTyRe^NZq?Nyovnf9W_4LfnS#y3r9_`>JP72L4$!d^k;ht#DH34^-ZQWu0 z%`SB{iu|SPF2bTekrRV7Vy!iYAKIYw7X{n(EYD5m;L9*MY=y@R##yi1>|#TjGMC+54>WQ@)i*eP zE!|9iuOw^9#CkdDIwUrMb4jP9ahSY=H~;l|en0Uj!Qk4VDDf!Y0KA}+Q!QYt?)(XM zMnIEpbwtm8wtq=4&dI&~??1;5)b3U98ubwK+j9y)_IRqvx;7Vk zvEmXy?+KC&PyleZ;U|0!U~y0pT?J+K23?9h{pJz@lx*W+&weBQ;S|&j^wM)68W0M2 zL683~1e=;xuY%ItTt&c?Zc6V35ulrI#EbA4D;F4%MRmlBezg7WAdUqt$%-moqn0PT zTyW1!b;Ea+(#==T7Vy;Yrza+Js$y$hQ4a3mT-8N~@ z8Y3dm#Iwm&0D(42J9)pmhzZWPj!ElfssO@Jy7jJRMv3tX+}`K}x9s7xiTt+D{n=tW zp`9DeD#-x;QkSD=yV6uyFFe(8mZQvf*Yt&+Cwi&V`ljD1FRdpZM~K~9fzWxwxhvFl zp-`4<53=8BTzb4qzDJ{$WSBSW;q7s8kDvWf1YHXz+kTecacJpO7dvNY6gh<0JPV)= zQ^k6;bjt5GS|Z_2GQwNtuSM>EY}8P49`;PB^acD68Bom%=WODE9C{{1A$*@%ux+w< z>&MZ`24{9Va@({kBTg@K=h&Gz1d-itn>F7ZlNqIXhCGbTt{CxDx>~ON0J-;Ew7^74 z8>PujTmy$Q1Wb-37^UX?(1v1=YaXa}Pm&iK?m^X>QvdZb$-DkWsHZ+*b9BL;)cf8VYmLUbU4tzB{{|JFdakmFjm5zHBW7~{E&FUakm$XW zoymMT#*^0iweRZa>D8&wiYTV6(`rdz%X+p^@w{3Fx8$L`zvJffIEh7E^XA=5%grcv zSIZfX* z$_QzcuPX9J7`||ze+RQWxGZYURti!sKA_a_wky_LjhUQ!p=shDNttRZIWtijaq$KU zT4&vl(GV&P|FZyocLx_D_I4;$x_MaO z<`8A&9*84|(w+iJ<^@ljTC%<^H6w(Y&P)~m39;YW#@eyp*YK7J1;usv%1~0goRpk) z#V4E#Fzpn-5@4CH1^;YXOK>m)K$Js7mu!k+oh=-7+OT3Eb|CoeuScGPRQRHN7Jf6vT++5@1o|%*1 zn!>7m9+=}|s?|MRbXoblf5vET!K@w>H%K@gb?iK4gBAPJF<|rhm*TKy3JtTK$5-R% z>=&AGNeMduLmPtxLT5O~+C+T9w{!hpn_JobLd0)TQ7ZpF=QU;BTaA}*l zwPcT^lqMIXAHHVfG}f5-%EHe&cBlqh=&|bR9CF*EmXjYE=hO99RCv#ym6~C*qsehd zFqHCs;?OhBJ7Kl*IY~TOPGRTFFNNPa(lLa3%FidB$7RI+`8}^}nM@w&nLjYTqiD=) zq(2ZFUq`Q?am`LEo1mt`Twft%gFq6L5$jwk#& zDJE^@`%Z0|<(Irh>>+(zmiIF_x-1kZH*8p8Ap+>4*V2uHi~e@Oj=hJgtt+rQgTHTZ(P@Ge zB4J80r}4ow(`<%IB{9_tti}@?0mj!is?6X$j-eYj%mSyKN$v2gxe8*}VNYXuQx!Qs zpO<3jt=$OIt=?kZ?lST?Af9W3wKWJ)7>CQ8O!xtv05(ezs|_>FgTiYEXi4?#>+myf`53)5DY3|vx zYG@pO>gwz^Y*ls{ozZ_fXPSCBvxLbk|6c1lqo*C_5>48Y5`@58|qw`zeIi zl}W;s^4ejkPQIzq6itNVDYLD!pa;1mh~k%aA42Ll)?3u3e>cz>g~26K^lC zd9=Z)xrzjUHh@_0hXzT&lWoj4?60SP$FQ|rlb!J;H;e(fR`?NtRr3<2>=q&)Euh)q zk8{K)v4OdsE8F;Qa~wuPw(;k`{NjQz#^7H5^p<|8;(8ii`J^B{@W;GF|3;EeAFgB= zU=8qNzYhd-^s>OZEYI!KjJORfMJt@HT)xDB_CwrDD&L(cQ65oHfaneDR1vXst2FNS z8hS4JcN=0Inq`Os_t1+hyUGLi#LLGMwt+USUU$s@FF8r}Uvjdw^GOKqzw(!i z#I)i^^8-CDzn>!Y-Yu5Rw(%@3N*I~e{#v|OuHw%bUq zHrAT9P-fEnnr6OUzss^kjjr$pZsaT1gEKPK`g*A((N#G#QmiCZoLBZtz(=9%$X80F z<$ZSNrRo^egldXbtmI$+O;&!IaZzUL={I9>=eOKcWQ)*8Nn24SA1?gVwp8zbh+i|! z^HNWt&W0x?e6KVKCGN8jFp$o@^V|>Gs||Uc7U76*HD>X9|@cO3!+5L)-`f0O>t-y zKvovG8k>k7Fm+S6%+qtYwatfRpL81i>zfj^xZv;T2ZuYuKP>F zsJNoDbH+xyx5v9VnPb;S*M+55hicH}LZhWdFyGNbQjCBE@Glax%3Z=E9+e|ryw0#s z$>A+}&0YJFs~!{J{QAEE&c42%s#o~V(w{1WJTHkBiXU!_2_Gr5&OwPIUa=aG!fdom zj3Q4pPvg@y3QJ3Y!E+tEc010HeZt8aD=nph5Zm%+yH;RlO*oEs%H-4pyd^5{Ae`V4 z4vsuhpiZM1l)BzDQ3GX}pD$9!6shetaFmIkBMqA{y`+1gBrqx;8ArW9rbWrULcF@l zoYy3#=HC|})(DCw54uHv;sh6eol5-pw2VKw>v}^Ry}CZy-|#BK z=HrIq;$G%4%d@cYE#9b92BnG;+#IFm}t?gx4w0$g;)9HxI6IXxaDA zuzqY-cNv!`g~z$XB_cGFXTla5oPxs=-g?_(q|qU#cahe!Gaf&NM!+`4HJZ+Lj!|Ff z?u&j7pT1|{?>aXW#bahpX<^wR(g8*#tM*g6?NA6QD#+u-rRe8Q!ZAjm4c4*Jq2YJU z2%h+-qy;<=8##)p30eEo>_ehFC>$!dO5C9+Qf@?1+s3EHzU6ED>Ts{-{{P3;Sw%(t zNAG%IfKd=eMY>f$TDn6Kkd}_2q`QYsQBvs=7`nT2C;?GAhM_x#MuzS)zjM~P`JZ#g z1y?NA+TYLK@B2I@-jP?crD$43pzcVDJ>F~^p23GbS;OtE2(X;JKd^1W8SAG)|H?ZSK{nVmbd#f3a{&Oai{a z^C-j*d+l95pZdJ49$_&5Y8L4@JD@b`8t-sH{h9ucRM!1SSA6$N;M;Q7>ht62)!;@J z?7lBB^t@=#5#3t~mx+bBsz`JYWe8zu1D1oEL;II0sIASemPt81 z`yyz%vi6KYtNch!*`^44Gv7&L4DG7nz1NyyHIIj`*w(BrzacE)aL}pFmznCI9VFhi z-n^=a*2P64%9eH)5GMUpeoXIhqtdmEmnwYN&yh_frpgJdNP%L%kb{G?s(h{c2?11# zKy`-lPp zp*+GHRQQ|pe6gQ7flD^Ff?N~a5))&sL$>%5+^Iem&G0@TX-t%G9K*@(ErSkY3k3W*V;>(;^_j6m+c@Q>;6J}saYZJX$knh;gR-{6ljzROcbSplO0Vv3QIbb1 z%*QsOU38Ng?LtxlQZFVwT0Ao}tPW`cW798*Hd1}@aHLHngLJbgpAv|-bOMBTM-Y%* z)pS5#vmmt_%z1_CSbQb4fhPOA`zZk$hjU^%$ORrKJ{E>c?d>wsUg!`WB17l%3GV{u z*uoceLBv!#wojn`)p#w!5gt^`=mvN1cKM zWJ8k}aNC%0*X3Ci?Pb|7__7$9Sp0S+u$?~@WS5y+0Qf?gCgMrgP){~yz# z2nWhtbKu{voYC04S938xQqDsq^F0Ii1@1t7(MN~?s})bpu>KgKx9)ycAtU!i)P^^C zDNyHr50J0X*TC{cX-CUS zPb9}(B+!U&nl{DRx3{fg$6uFgFHV(xT2AnZeoNSyl1}E5WRV6JjsLK6!c<3~PB)7l z<>i@C*{F2u?IPU-6!M_4?0e;67iH$kc6E?!bY&ElJHdr~Wd>@Pe&JRzT$TqOnUW)6t)sTjh`E0KgFyoR&5+5{=!^Rh z2_=d0D9?b-4nYrk(_=v<@ry;%fsZPGI!|kGQq@%{|NZEk<=k( zk39Q7N--ZvN#EPVl@O2EvNP!!&!BOk+D&C#V|mIy+VQmn?CK@*D`=!gu0E)pQ&Y`Y zhp}E=5Jyg*tdfi`=A>}51rZum-G_LD?t-@Th{~LfSUk`*Vp+0y zsRQe*=}d^6-0@JmxdxJRO?!s*oC?H`5ZZu`$ePdm4SG!aMcN@x=Xpo3K$X z19B>OAv_4LG%3QYmfd5Wo83O8_fSpgEmsCdOE~P(@Wb$?mJqA-MyhQ)q_pZzI#~kc zoXFXzQ5T?~gm!z3gGBb#)2+M=@Rp$6WGC}a8Y|#aZ?#Ye@!-y@TUXoLa8k?+Z{In(yv;hKI!=-YkQOr0pLgcu85= zELvQ7QXqk8dA$g+0t*!6XT$(UMj4{seshD=X5>p>q_VP(f>Gr}6gts91h=qEUBHe& zBqB!L^ts0Sb#}uq@)vPa~?0cMu1$wC7Tobga@G`D-eG3>h z`C)~%O3}sB&w)IWqMdjdSlyEkQA&V*;u=E%bfH=>k+k_K`w({%BN>;Zx-VrWKj3Se zSA$Cb*ddd|!QS`PrFPevn|nHX*@`6hoLV=nni^AwU-{9cc1qX>rImIXGTC|-{KG`M zS~qPpL2Omqnl>(FNhGdFw_r3U2z$>Zd$q}ry<+s#LZMbHvq;Ew*P0S3-^wT-~ZGK?)VNE6TmDW55w=m!iR?sL^h!+WQnpurByuzhPh+Qj!xgsyc|w9%*WL@ zX>i}A=E#&V?w|seHWwf(CQ)rI?>gp1wfyXoYQ1IcyY}g6rH&rBhi)ET8A)vH>7l%n zy}z2N;RFFc0=9!JGk`2YvO#Pas$adk2u9@PFryV01EK?b2p^@j?sme)CTEab!~OuE z1qcMFVzE#I?Eq}s*l&8f0YP}=L|;ug1OXWBJpq4VwgmdmtC8zymYUw~HG6k=LF3BmKLJlB#%kS0z>IAYYvu_}r0)vT9M6G5OkH)aK$Cq?Z zutqLJXaEGxn7U|xJ^ztJB}13ageeTqYdsUY?&G@N07E^;Sw5XhRkJGXDekZF!%UJ4 zkh%9!eDtjsDwp{9@deU+16LTN!%g=&IPk=w~VSN=8!ZhuotSq*bR@ zbJWH1EemefgwVpwL}dtoW`~USMgAfC{QJ8x|G&9?BB*@}pVL*)>56K{jn0MT&7YW; zE=$jcP6VuZsWcqL6q-e+@9EiGQC zm?k!dW5-8MKM7+vo7<6^{(M)ur3uSC7H;p@6TC(*fNg*O&JzBJSN`(v~0>j&BdE-$mzcvTx@W^(pQ0Nf2qqwW%bkNjP+ zp7Ks#L{Ms1RlU2=n;Ra6;e&ShXBG-`&PAAkG#*R13wsEY@P_kWyL*RP#!&@!L@W!4 zbrT~eGhLu^dot49`q0yEp#^%l1e_;;Of z4`;^MpZkfOyc@h9oy;!s8>BJ)na$xtfM}H#h}}_v+a9Gd6NL_^ta$Thx8=7~zL62`o-$&=5zr-E_B&PCnSoTFOMB=e5*R`v4|UFa*?#FMUttaw31)n>tA zWV)?lvlR@)2gLqtBS&t6{VCWB>4OnN0K$ZrzSjqdoxc2jx$iv+)BwB$5J^2EH4_7M zy~7dzc%+Ae-5tdID3-uFI9eA~1Ns6u1n3936wYF|0A2yaELXAq0N&_UVWkIoKSKIo zma#D+*y&?fioDrGqb$ykV8NV{_s20bE7%6@=mEBoI6V7cc;MBbu}JtgDD^S`K#Q|2 zZJeD+`xP6RO{d}ZvoJ~!Qdo}tCpBP@53;LFIrlicpAOqv^%ThZ4DabF`x3X(uQz`c zV;Wwzj)m4UUi5`TY$$hNqDDv7#O2r+Y#qV7axzg-(M38c_)h0G{_FOwG`kEfdStYe zR5VsFxx(sqAi=w?3@e-dc3G#nP!9l-2lm3c&mY4c*KN-MYx^uAbl4|Td&4a<%y~wzx$l#F9J69C?QCZcclaQJVQmZNR z?aFZ&&P*HlN%a<86sVPYf#}iR%99M-dkgMbR}QvFe{_1kAS*WXp&g2bpIyvUU#D+R zAt4D)rp-MHUa8`6oq2Ge@wA_HB&Y2|9MHHqV1}Sk#Kapr@$_imA;q)w*jLx#hn{TM z*#z>Xvi!lM$Kc@=2Zc}Ic)LjPozJmk)woTOQ5BauVgC!d$rOpq?5|Wt6VDu`0}XGn zV6#`|I0HXF#hA%Oi(p_>tDqXa`4e&2MUCgqz>$7X=A>%mQeK^G<6dtLF{P;Ahjomo z7phjGf4nJ2;~?6txk6C%#(|~=qsczpQ82ueZo*rs(;hxH%$l6=SIyO~AbpCvXBWgqgv!1jT9qLRkhlPWvos%N>G zM`?K)@q1^n1>z>&)YHK0rZ2pF1!%$KRYwqep!X$;+}t&Rxv6vffAVC>;V0w0VOD;A zx#^|N_V+x{IRJccdAG3ZywSb54{sfaA?O|MXsO_l>YZaHn;++`(Fjr5>}q#*%3L&@ z?`0;(&LOpI5qM|7^Kmhgki(8pOF}+RYYaOmXCwfnh7|6wrtr`(gYlh}Rte{KC-5vx zte0=5;zgO^qrNo~Mv2Zt4B+$FC)Fc86OP4gsy&9E2|YYYIvb|Y_Abd@`HGpa{2zBz z{M5ACcG6MLa}R)`O`o{cYR+p?OT|nyWE)NM))Swm6lathkjc)EsrZqfeE!Q#_lNo< zPOOIGfflz26v2X&-EkTD`60UlGIa*jH=fTE^;d4qDc93kP|IX5byyv2jL?VK@T z7_NO;h>R1?srZu-?bX|tcD!9WU)1yB6L|*FnXroTRN(=YH=632h4Jfd2YC|n*Ji;3 z3VS5Gt&l|rh}QgA)iv^+4Ccw$VA4^G;?ms8c-fa~Gzl=Qse3`ft5IiG$j0gsYD#R$ z%IT8)xPQ`NEY>={{4)PE;Vt;DwqGb=zB(}n2U4TjG;Tlf40T}mNUWqaRsbc4Km>DoSJ$TMnCuO6MkM+{OyHcq{EtBoI^QJ2iZ z=xOr-P0GgaS)=Ys`i8}~(sUBdFUm6MKB{R@zC)Zq`*#$rqHHoyy-7jFi?ubZSwF@5 z8*|dq%NzZ>|6({*fL>=3cxVF$|e%{3}L?Hx9w4DS>hZPvLv`1AVfxoZ*j7}gyt%#@l z9!AjPGzi7EwjT7O1qnk^Vp`&9F(!kD)_BzokLT~%8zon&#)=%lWt7h*fG2SaFG zleoX-DsC;6O|S&9J}cj)9Q1v`zVm77n#t<3j-I``rTR1X$(XWf`gaK;S4jRhpX?7z zMqeDPvz2KW%D4ON*>U*8Zp$bUK6Z7DOG{M)a8a#Hk0=55R_)Ef=~AzNpSD|i3mKG) z&-_Cw)4X#?VQFRGG&CAczuUunx3D=x?Jz|IJI!Mbtfa+FjVl-ds0K91L*-Z{INt0Ri4`!9xACSdXyM#G2)( zznTH)UH$^Q@xj?xIIB(1F7bp`sZC^4t%7mgUxK?HbrOnkNfFaip`-}A9-qm82T)DG z;`0J7|G(YB(;I)SJp;(ik0)b-OY&6lWXCpk*N?RWjL5Gh1HMkiyveG^(D>X2 zKK#jgyEL9LDVvWnRBpq%2RMrL)HA;KLo+)aWdeZWe|}(+WPZm_Fd%xd*j+5CxiE<# z-uE=ZMTgtNqF-IdLN+<8Is18z1UmzC!4Lbs|IN>B)d2IOvan^5p>>A!U~|cF?>^(T zDN=I0d^2ARtL~+SHM6}@2QdS~F|1*hRt|ca`}<5`p7FY?{Cx${>0XPD(YRax`3~>F zc{g;P^zQsC!e{dZN2YNJC{waBPc)#EEnY>ytc>7ps4{p1GAVQd|pI;v_ZFyry}qN*J`%NZ7Pd#jUt z1uF~(!v93Iza~WANo9FCmG5RPRNVPyj<*~8c5!T!g!rCW8#h|Q#w)V)2?H($MfvaU z?9O_^U(WenqORW^+cwhXp0azZm|T*p74B$rea?x8PXt^rFC7Q$ulGi6Tcs z#en>u{u0uPUr$_WTo4VYcA4F zBLC`b)=Y9>OniF!0ed6BryPbVBe2ubYw}msw(Bc8nn0^oO@C2z(l|tyB}!bpFW9X3 zWNUEDI2nO`(k zQ$-0t1(qw8Iz~$ax7`#5^s`gz{gfMG?svMrCBC-UvS48qc~_UW#_yI)=wpciPr-A| z)|Q@@@0lKC_A}+{)1+obX&D!;@y5RzF|Ngj?)=z;o)@t-Txv9=d3t}-4sZ<_$so~N zwzkyFCG-L`C089t-j$@2kPWVU!Ajgr7tteRpl)wNy5wLC+H+`s}5(*Fa1jkzxq_Np0v^Fc^LE5rmz@YDwuIEeQ2bE4 z3exzRPX>&qs%(w_C^vCbIq2y5mkp$0rtLz0ZK!3^lt3xpOm=M$3{#-39+MtWoY&Nv ztqcnB7Pl=XEbHK0dy_Zt`ymX2!E}Bwn|{5> zs=mV?xXd1@VNpZW5#r!#PgDKrCuK+24`$@v$i|+#_o;&6Q+_$JQQho8D_9;L%eyU^SH!^yBDV%N7cENIV(5J4~ zID@?8K%{+;P!OF<7N$Nb_$^UPSCZ&oSSElWi2T}_Fm_!zq%Q*3-GZQdUd5jTp$s?4X0ip*IWUb4!683@*uMlAn`jlr2j{i1`t=O` zl5XG?AvBL;n-}gR4|)_8RQczH6FudT!LRWMiLLgS9k`by1J$bd*-L$a{v_=Pb;|CTv{)zrR@gqXI8yA5&zrTuPITF z0=2eo5B-^Q)sV>cgh6v!12J5|HusGbL6!rA=;h~xP#QqU1W~Svw{gOoPX*1ff>?ENsmmP@b?>bfM`r1SJr|;!7h3AbX zviwKfaVyhil)dXum6YX6ChCx4avatdU@GWN{|OYya>Nf?E@3Geonk)P9*^Njmt)Ve z>TFi0tG>>#<-stH(kwZ+v`5w0hz0Ch18XqUR6qB~5ubj^y?W0=yV<_!9nb##U*mTo z9;QVyzVg1GBSy}hTyG%u070kpN2^SqmoUbZe7M7F#wmaLk?82>v<_EqhyM;}n`LW5 z@It46HM{P(Iz|oZvYD!fB74j&p_|IIRdn zjCRJN>6ex`{=5mi%HvbWk90mnt5!(Ge8!UoC&Z`zaJ>02euU-p{59VOR(m1mH;5== z9!V1nJ!l^ps07QA(eyCI?bNoz7^27`=BFuLin+%uuTxK<7k0&-x^5?!(n+@jzVfBe z=6WjF`Dpzo7;-0_hRM)t$tq+rLz9HQra@t$46|MG zVy94H5z}i{Rwn(r+=<1+85`bs<@kLe8Qwg0BX@JUVBg1)(NVgnRV+aYRhXW9u({ffTC{w1xfl^5QTRDda_BMPTq6xANMyw zPK#vIH7i}=NfKfQV4^Nn#_JiWx7^Y-kAEtB%vcXH)U=Pb>^Ha5&Nx_iTMV%Di#AO- zA<0TD`XH(jJ*;VKAF6IzF>I!^{DywOzVG)37ADp?!e5pn8I?P{qZ9Q%tx_`_&$3E> zjw78W>k=iHjcwd`k|YEnKV=9KGipBA{3J+9=rmy2IY~;c)6~0SJ6JNv&&AEs^ys!2 z7;018X%S@M-(xK>&!CD(ar8C^{4+IJF3LJl`uD`kj???*LE|4LC>)VSTakpysG4^) zET9Z*_v^r$n&N41TnZKiZ!jo9DliG8rYW8J(hm4!w6xwm}eG%33X-bg!0l6RM>@TU1+H z&8l#$FkiKM1}rraEk>WUvo1f?zG`*UvfoyRy0k@XI*h*C6e&}634u+Q6e4yv?c6lH zL#7s)K2KeNHs{BR=J4+y@sziw83{I!r|PH~*;^&~6p;@93k z1k4u-)8ng<4J>riXAvp73xn=56MeSLc`^l_2+XoOprYZvFE2-$OD5olJa z@icdBjVIPfq<)Yz<~;)UJOd-zNxbV$Y2DXn*h2mj@&pM+*NC8_gWZTZ&cv+yg>C-Y zt%>+bkzY$5`BpxQarGhT(`Ku)_gqW1$;imD|yb3~zBB;ga`U6ISD7 zW8-0s0&JyTv%>+ObmzH$5M!lb*)=*Y?sgH{q{Kc z@$Ha~ug6p$@9mZD`buz#gk};zduKUxU5{gBedD7&aw-wHY+PMSJz&Xw^zj65LsG+D zbuX})TbvZ|q0KF3?1x)6u|{l*B-{>DxqYN`ivj)ax&z*rDudWJJk$7YN%O#VL_C!* z#k-!wbZtjA&}f7}AP^dpUUb~LQ@}}jWyRP}*J7&UYJvR4VEe>(;#Z4ussp(PEs|Z5 z*MNh+?OU|5Aa66}2%-h>((J}NW9MZ(k7$zv5a1QZGDB|x4VGV`w80^_Nu2W`nfLQh z$FCA<2G>{Bm1YsFpV*#+Zkk@cCb6+FMN8DJ%eOD2}e98xvf*PV;uB z#$e@*P2&VH(+N^76pcOXlfHqusvgxmsOTz3 zL#Sv48LfZk-56#}N3W*-;vpB^uU#rL6cMxB@%SN%q5v&uLPW>Z;&nZ$c8ggeE#)fw zqiLJ`JdZpM_!_6@R+?o*;PZObaapOMH`jJPQ<~Y2`yYv%-*`Njy#+63F7~)@)qI3V zI5E=RCrvIkT+}SLgxrZ%5ITUbMQ?w_P=7*TBxrU`@g5YC$KMT?9GXzEc9KZ=WLyz@ zZN1g;$UgzgpbvO$;kW&WZSO?D%I$CQQNznL-HXCIs`xojXO+^!X+hN>+b! zIvi|IoA{?(+leBmtf#G|vko1p#-*|$cioPJh|npg&*h#dK;~ZzO3+Pr75U3;Z*|ti zw=)!i<RnBZ(L48}SG6DP zl#^E&ao(#_oBsYC+wkshgNW~@Lt5bZ4}I5FWqrTZqD4C5(UyNA9HJk;`odVR`_)`g6Xl-M|JzifA6WN5{mWe@?fBuUsq9xiP^H`My#{Yrk%s# ztc0r4alDr@B5rf`%2_0P><4S>@g)3g`gM7{<)ekdse(|S+`>^M@YB@P%<{`2oIZa%xy!OnYuO*&h5XhqOi|S^>I!@f^(o7UaS`+R@OvZ1h=V^D4lf? z2&xl0)?-oNsFg5G-9D%Ic9N7)gE$24J?!6V>xZSHJC52oq`@V`}p^c z%fOO|>s@UJq)R!eVylKGQlbZpYsP=cRrn1y<@V^Iw32Z**e=Q(4L>#5?Y=OW%Iz{V zL{}00bRTFc)l2f6Dyb=-tk^@HT$BbF#>{b6=uGo;R*KxMw_0CYwDO;5FJ|}_N&NI{ zca(3}Dob#j+?}CnKt?+$+}1nFx2QES8<&YrRw4Oq$ck;W@&p!W5xb(4?$Z^@`u=ux zj%_Un<*I1a8WayB6niL&{r7`puy-KQ&>iF2=6bgn8uZ{D?x*|22jR|KgNNi#?Up}-TF$8#D~OdG#h=P!JBf&R=!Qwjk$Qq=9zFMb z?}JViuV1IHG7||{3y-FiG`&fX0%K+b$v25Pl=h*Ui9)}zN1f#7Z_Fwt-RI#UdWC6s z7qvSsx-rkD5ld#2&ch51(p5tK&X+mNvpR5fO)F`bOij$9{V!UKv0nq6(0_EaO4l%y_v!iJ55R<>wxISL z)vK{cxrc-PiaYyGx&!MF={Cc7?y_+g#a8eEF=EZC*2<*|32>$D!u&2S{uYiS8GJ=^z>JM4cYkx`;OOV<$@poob|J#IGgpN zQVfpR+ekC+ST=_YbG}@mY?i(d@HriNvkr+uTJ#hXlUhDf=tU*Q)_+hN$Bj(;nR7W? zq7bQ~ZK@QX@KuPNQ3I3Ittf8x8dj=~xfy!Wmv8beC9jyA%3LW*o7xV+n9m}?&=-t3 zI+~J@B^2k+m=8zGL$e*`l&DOG!W;a**A==wCn@_`XS(phfSz6oY(k!uwq1^1Xl_=#q@IYwz&H|Fr!#t47Q5bVWlE&Xr=s6TsU$Yo=aTB#_H1e zyfz`p!20;aEJ@wm0e@&vziFgl3dcLq)Mm_M1Nuaw(cXy*tB%6yI)gjo@}}8Cche4}q$^pa+Fi@QuLUmS2!B#CEV;6F9qF4Px1`TT z9IMlau>)zJS@#%X$i6eS7%Mmhlt|o`6%z$U=I>7EYeA?Gm8EeHmHJmlfUPr(J-3Bv zzx>ozTX3+ma;p1}LSU9(Q&ZXTmmr_y=^gZ>L?vTUMpaCf%QuN<&>x&>-ajQMJd+%w zZt@*tI(~P<=hYo2ez-L4B+u+YebFSXBG7M?hxoR42mJaLn~PAlBJIVw!gje-^w?*d-(xKR zduuTKD-&W=5F-Y(;b=DSCIhQE^o*i9vZTS^-=C9^)Ca(7LgE}*zYXGhZ@jB&I7UYv z8Xz_;#mj#ECdQ_^i-~;|;9Ks}??ivFg@yU#gPx;%BMGWc=a=u1F8GCa*ncrUH`t|| z6h=ks)~j*ShfBW9rE>TP!K8EcgMT6@?t|lqjl9OApg6~}1YT=Pab$p}H1L~`J^*SB zXRM(5XK&-qvDnqQ=EBb{fVbn?+XR1rX>08y)p8Fg30KKyr=Y~=DvRDA>^C(7z>RT7 zKMfOaIm3_AS3yE^6x(tJmB5>As(noJ*%o_b+bRDQ?ZpqF#D4yf*@Pz0otLDqL%)7# zVvI^X*Kx2dQ8~=s?U&G&xQYS#eoHko2Vcm>U z(sj(jSIUe?DF^kKK*;s{F;ZKBtr3z%kzZT@@=oe!(Nd+wG8zSa(!*^Tq{O4TMxM9u(^VL zVqqr9e;jrXp0goxWzoS(%nK@xA`XgjW{pd<2ZkbqYKZ6oz`;g}$Goq!eOS2DB4w89 zXOo@ab*JehNn7XKE_&CeP*34MAIX!0to+&KF?y2*G!OqBJ8AFe_$h_n$gX4Bjwj|O zIFbr8iO;XIEZF`|!6I@u^qSd9xyd7<;rch~jYQ5L^GZ|G6BsVNhEH&enoC3)P5MgL zM!lZ4U|B!KWZ|yaq>7-hGOy`~Iv=g$ff1v{h>M0@0#7m5Xd3>kWjR@}*T7M4SOYTEC-khGGQXjkSyJ>^YzE}(0%GHA{DA~n zPptZq29|!g@@%mQGeEp4WE_Lb5+`FD2$6}WUUp8BH`Z|ErfsptbNCE9XpE_xHZgN@{M&XT$_3$O!Wn;^#lqR_vi| z;NRDByUQo;GJ;Hg713vgnRv`k2$eU=4z|_IS7seoLY!6!HEbQ`^3J#Jg4efL8XD5w z^+giSG2bPghnh|ph_lv_memw3RP#_9GNr;ly{~C_K%|9Ku~i&yX0Z~Nx zj|g_11xf=9x(I@RK|Pox5MN3&ULw|YEN%AoyXPweUASJMq$HnkszH8edh$Iu2E=FN zFn)ghTd-p_n|OpKNcraC$nzf_K*nIJU`Sr_ye3B2sjj>eWRjaH76{;ydPa{&-tYF8 z`zVkchyG~=zX_SXzcEHmW@tE8EUiIQ{Gm-=PV_JMX}_?;2e&A%a;=L$uVRGAL63U# zNdR(7sfqEVu{h;eFR(V=-W7oVE{AB=54$npr>^_IGkn`tpagh%5e9FLK?K9$eqw|& z*Z6MwL$+9!)+t!~+fCqre<35cDIK{1L26DF(o%1H4;i5aV3+FdcKRpuat7y#A(oUV zDbeU1uHOKC_pfTknaqdcP$sAAtVUw+imWgqE1 zUFq;OPi>?vs`UXv)?APdzp3q~!L)ZRghB3WZ*3jqU|(oaVa6iauecSyAmAz}7MrGW|{u;kHNMk7u?k)Eu! zKbn5aWtu~kzyr5l1QT8NHvllwPPoajlU_{(>15V^9o^|FF}sGrM5Of;-F9QO(5Eak zO=#y&E|?lFE0W({u2_nE7(52jP0XDQhmT~<`{1`ueQ3pc^BskxWDf1m&s69Y*d1H|69pS@_*q2htA4@N)1PeIG0Q9Wnb9%5 z!;)7Sb$!dl@k*RtAg+s@Y`7t@m;K6LV4VB7kC}~AfE#d{OALH&F>UG>85N=9XP@Eb z6`x_B5Ow;xz^YJ4eo!Svl7GA#zHzI`h$H~%sHxS+zR315+NGypkDO3xf}VK zQe8arLPoBTRe)9Fn7aktN5a}2R^kIVztX6EkrH2-+8fjh5doN(yO%~Nhp*L^gKG_! z3k%6ai$M$0^G{>L8japZHZTbPecd;~%re3xR}+wBdRr5DF2lmfE&EveA#sShh$A(# zO=-uwOqo;D=Uzr(NUvgJKj^hZxwh%9LK#`%mSRSJA(y9b;F>9$Z;5)H_8ShXk_lJE zq&VYUCUp#DX47)M_t_*`jD!?bQv7;Z-cq*Ka8UDeuyR+F!>ulSA*1WV_s49+@0jen z@R{PRbKY{Bs}H?LcZo8MS>ra;*9(_a*k}eWV`>(aEiGyl6$iF9huUU_%MZ9GLF(3s zsi_~Ol?>ShIy!=tp>r<$Q?;@*ls;y*4%D7@N6`9OIt|73>_M=`baE?^)%Bb?%B$R= zlCEh_bQB;yFQ_UEqUJbAusxc~85t4ZwV%(6ww%wx@;*osMQFE6b2R)fw$3uF$^Q-e z1H_36Q;|+ZK%}KR6p-$Qfg)YfF=B{$Fq8RyVS`o<#VB^UOSvuzdLvuN0x@=1wFaO+^cbMf>Z6uena z;N{HV39n`a9H!PkG|H4JDcv(Pw{E}SavJ&J<@(-X_ z(A*qqMc5qA(D8ksrMOV!g7axcF&{-2$@kg+cT78!O@NjGj5q|IwHNp1Qu3?G{Jt_o$ zv?nJuyJns{dhZne$@THd4<_sJ!g=&}Nh?5D&&*I#9Yrqnz50rVEcJD{pssCx*Hb z(}r34om>$JWN46p(D^@XbXn`>^rM}PZ4RlxwMH`8QD&b?dbe5knEMPj85qqiR%l9( zlqc>>kn1uTtu~ATVnTpvo3J~X5u0@lk4g7d-OcEHick@kYoomFE~erhQmMC!^f^x*W1>dFA1Y5KZh0E1Pl5Ssb?2EFf}*x>jrVJL-RLbN-{`>_9btfk8f@+XD)+gJkszQ}Kn#e!THMZCE0+ws5$3(wa z4pj0M<%LN&KW~FrBFZbnZ9p*~6{io4EuMc86SzDWdBPz|>B0*Y{TZ`j)o&zv+31JT z80kNO?S7gQ&2f)%6lR3?F23u7UZg^V?iKB1j%}TANVOb2BlRK^FK+=BGL0Ewi@am^ zbPV4V8YGqbF9?qgFnwtsIC2|R@{m=HJwD(Q8>x%E;$q#Tu$#%p!V|DqM&EAAJ`DxXAxV3}x6TFSb`vQPtP+uQ4@}5EJTWW9HDH8^ykP z(}C^YBx+;jkS5Dc%HDdJmGgWRPlPQ@E;3S3>TM(e#o@6=KVt`ZSrppzvQ{Pn@d|eK zvHio!2j|Wwl|`ZwCo>;Kdk+uUw_CC8>f;BA?aHElN_Sxdt5(K_oO5iVf5^t(r$!kt z$dVbwh>q4uTjs9Ye-?iKA!qU#$F&-yHokKcPlj}BP7*!@9NI{Rw6Bptb*@SlM}Jq?$p8V|UhQF_UW zPN|2(cL_~(b??~}J3q>`q^5(O=?|mb(In3{)e>ofot+tIsj1;7C^>xWytpAeu(hN# z6)`i8$9bmG&LI$E4}T+2{JrGUUPG&MWxqr4P;=e z^}UW+e~Jl>39`7kdXuOr(G4W7)PY_{zw0AlYjRiLd6KB4GN1#F(f3%7H!1DK_%^4O zULXvFiegHh#l5dfgVhLUDW^@=*5@ddQ-q?;r^<(;7Aw__MT-5Dzg|=@8mvZAdhs|K zD7ht+2wxY5S->730EVstVm5q>1xfllJ7CxL&Kx+k{i^ z()YTRB_a(k#hz7#*%>6NS4{}$CF?G+ZQ%zPY~8Y}o=pMp6*FFD@aTSL=}yVv=O7e; zB-AAx-;)geR=9lU?en21CDD$r0iwV}--DLd#XxK3HR3S>@VI6?Nx-v=LUm$m$0f97r!`na+$7+1SXHwd^n~i z&T=wf3H*gYONwdx9fJd2zge&+ItI?WF%bmK3siXU+8~n-b_fjMev9|>3Y{78 zy<8eW^a5eqyaUlO(eB%PNvLDEg87< zw_*}ZrQ=IOFbRNnaCN$vib2xITlsZ^tYO4$Dkj!(?rres(id-#x`eJN za(YgxNeQGTwS{iL!+R2hwva1H#M^c$LSkL1D{#oyx0)HJvKV(JPI3$?%=;PCumhz?_HrEH#c!fB$6-|EkSYiR0+)Bp~W$cQNKxaY{BsF+g@t^xSPRnx(SsTuVX zTAKW=Z@xW>=j&1G?ofVyj$ywsbrmwZNdmI#2(>c8I8LT><0d0=i|^`R0^L+#j>!OE zcVS+)?_BP&)f7B;T{GHiiLB@w`J)r4RMzC&v2sa5Tw-w^&WUwZS)^Gj#ZO^?gG*nd zSZeBB%ED%inRUX_6^ky1F^)U%UF&$`d-aZ<#J<<8HavzV%RK|8?sbug;F3<(q@wIA z`E?3zUGL2G6w|z`&rcxrgA4wV#H{ON7ZkkU4W!v%y$^}j>n?Qn^auIg?(bHDl9Hs4 zI{{vHE0dGLrG=0Vxt7NeASq70gxv!`4ynQYaNpPJ+yIEFqpICC&yf{6N#) zot%~|O5DJgj)98msx`Su3G5wdwUh>bG|h%h&WNuu8w>DN*7PX9(GRCBZQ>dws6)hx zVx7Hczr=>Y9uIB}r#!hyj^`wfBvyTnKkzxEob-2>v63w|%#mPX^ z(mmckaw5GI2#mdmz525Ff_{|&-668HB3s@RE^OzF_Aeit$q`CPtK)D?!!&GV!lIib z`c_&Rz~*%rWaXS*bI)vRn+1hWLy4PiY{KFOeFebykEZ>J)5n6FQ{UPQ4rqDG%GXh~ z+gVYtWX0$gzf3>oA4HD`(*cP9Ht5rIB58my^uDIRC^_>ZdlFzIKnVIG@7VG=L=D1` z)iU0hJNi!boblr`9;_kiJ@h#&jF_YFZuZx1vLS@5zv?6ydcdMM=(t~WEr-=IW-tAbv}W`(X_vr z7g*xpi@xj?!lu0cPN={U3hR*VB?%-NQm~VFe=o56%sQO_r!zt1=aK2uuG=EPc)4MS zSvau1-oLcC#4pIO!IvHvhq;RZt9+m$qMtT06A~DF@+~nMmMP41?iV9;gV<2Bsn(PV z7#ol%Vd)z?xhVI1l}%cp3&b7TZ$mXiUDnQMN62F=HI3{E#7;a)ZT0A1C1tTXOtl84p6!c}x5pU+Le5JCee+{m#-SndFk)EQ^G%2wF zN^TN1;Y>5cFC>zd;;kP%f(+br31BLNZYp0rFfL}I7hMOeXb+w(4eq^T*JOmNYD&=n zEN#Cf5!o4t7yRY%7&znXkes@iX!rJ-`fKZT&)skT^dduOVcDpZ%<>RNfWB-YGn!(k z;{7_h!q1+fAC>t6`Q+BUC()$>9*tr`J zeHvp|0c)*!13JY_vIJh@_V-=XVIVP#B(m;u zv;Dl0ai&?5ds3*$ZuxVK)xr8u_Gon1&&$MxV3NICo{e!R}na zXXmg~cndzbH}REfAwQwCa`G_2(7yjrRljNNIYnZHfyTIsHAR_$;>}l;{+Hf1dG^JB z$TkR!YVqOXpXO_7pK4zZ(El4$Alf>ICX>*ofKe^y7vREt7o=|8?Gl!z8-Pz0;wJgJ#T zNRQiIqUPg${(MMIf*Jf)t?a`!Nz-=X=`DLQ75Rp)TAt>CK>-tA;*S^YBprOHq(=Z> z=~74lV7{kEkyBi9NZCv;@4xUgP5GVRvM1zx=8@jN;-BJ?GAah?6C*?~!<5b`C{wck zQ41cGEpQmvlwiu+NQ!9)Cd`mCL}9am!$ZS(YG*-BBs{@1_4j91npY-?`B(1E;2$O3 zPCJWlRdF?^|KW~)%bGYvqIv#d{uDYV$`vj& zh58L&Ih}jq9g1{DPZgAa7yM5ZDH89r$n$b=yOWE)4mtU=f873kdAvj4by`0oqC=8p$I5_O;I_^Nl=YW$l z!r2vx7~7Q-iDl~1#$98U(G;YC@eSElU2$=fsq-;qyW3ERAk;+Z8a7MkV?>*7Yw6#t zI$Q_gT96iUg~+PUv8i$G)jzJ&k11;PM!;7?ytPOT`eqBrCPiF)94~~Xu--QHq?43w z<=XnD4aM%Nrn2?kB@U)ZC7k~HrjvyiB?M6-MJ0E4VrL&myJqN2LC~JAsAey(AszF_ zke@uU?FLDgl~Z2hB6e?j?>eh2=3D}NjOjd8;XoLVYxLfTap|1E9&&;8w8%p}sj2+- zRRglb+bS+~3Rb*_vYD)O)jz(tYhCcMw1~MXj55yl=H8JF)K6fQaH3@=(}q!=dJ5nG zAO&qzpQ-`Hfc}7&qHOb_jQ3>8l2_zNdDE>r3Fr|76X2MBx+*y)0$yJrUa2ksEdR*w zy=}d>IhXbNoZ-%w?BTB@+-%j!wK>sY_0#~;qC0OxiL3VLmq6UFk=>Uk4egjSLfRm^ z&g(5D8F-wg^tL7Qr}YOGXP*bVjy~N17ql}IIa;k=np)SiwFwm#S!pDok|6g zyddf(=mVrAPvbB3QWBLP0Jk{hw{m(?Z<@!#-md=e z24J?R05567^9sRs7r)EHDOm_D^JC05Z+zQ1cSB-eaS)7so7?C%`QC%$Y!Ed$J}CB` zVWkF$7}w|>AL8F+@K_*nM^PVFxM`U1lC6G|+U!2frt9RlCc-_!CV%RdI6-SlNO4Q8 z_^<0So*!_zsYz^W?malzrn(?3>VwcH_dzlpX^c;r9nOg!b-ls(j07F|x&n@ZaG^@K zO?=q2tSQ5`^E#2cNAzQ2-b32%qh^#ZH~(gd)cka@2@pI2`*T3IZ|1$_M|XPO#5|hm zmn$9P#r;(BU$A(+*}~loer~&6aO#WghTh=%yO#73B5uExa3CjcG|&5D?IBaJ&14L`uY$-(&`&F zET(I5=>2d19H89YO>Js9_!RV~l3oVWk)`{+8+Y1nhmS;Kv+HhQnTUuuCEPoos2Zxd z@Y3kCoV0?n<3b$W#hrrlbX;94fl%dDVr^BiTKQ-M@Jf;iJ1l~l3j zR@VO+hq!)aq**bo<&$ku0FLTo(Jaj}dD>|Yt!y5sK`aB3CW7XKYThuRj^&(Pcafo8 z5TP0IvJhdxEwZsH^)?IV)|mji>*n<%fDL>}`!OVpnE zWu4W>_JZ(JJNHjXz2z+jAtZ5b(V!TI4|ZyCU8}U)bZ{*!RAN!6x+`T}BUW8(duMm@ zCId1#fhv#L@Gdv1htKL~Pm5;pG@Ze3OIvFXvxu>|Uy~;(r^7wKO>mFb@rGsv)>P)X zoTy`hg-<@^C=bJE9=}ss?zS_^@|Im;bI%@(Ne!AUfhRC2k?_#K?DwH{QjuMRx`Rp* zN2%{0_+jEpR@dSuI)@9ipE&wwR5a^Aoi`oIAfjxMibxN~`setxD67;;5B9vXlY)Y>Wcr;WXrG@)Lpu1oGE6z| ziiBU~-FJPR8cmLrvZSQEqUjf3!`L}qd~Y(!ym?Wm|1F|wG_%?lo%I7Pd2tbd3|8JI z^Csj>d5~wr{;HYJ_U$N{H>s17ns@GSgWV-eoEH(fsFP=2b+|dV_F39`3C$Yr zx>mAzAwBQX^4`NrCqvx?Oeq9`;wu_agsmu+x4icfR-1uX>tvKqIJlDf4)k2r*SR!^ zqfd&fKfH}L4WF!WepgP>g)U-r%XCiTC$hQ5hyU=4KG7v3!IPz@_3&7n(=k#ohojt0*+D zUwQ#S!!RTFog1y<4h8Tm^7Q3BUE$MF)XePyA2zms2#4ZlCVeR^Ff=j5G87uf*g}*J zU=dXkJ+%Zb1H?ed0Db^%9{vjxJ&{PG2JOIm>^kY%@Aff5BKgNz{&+7p5eEOCT2xh~ zgSrERkYBsfDK*R6&w6<0YY7lFnBzJ8FY*+igQ`4&W@SL?4umxo5Z1_5xvTrMBFe-v%&J#X}uJW$e8bMedKOo&-CrIU(mkGHV9>(J=oR^Hp#kLV_z`wLlD?S zct7`>sKl`bzH29BDt@39f3k13?~-fYA>E5dLkC%veHubZ*qHsG3Y2Z8*1fk3mh5bG z#5WaZOnCDSg~AzM;(AM{l6C}o2D3!*3(x@@Y={UiQ%nR_id~X?ZCEOs6qW@`p8&%> zH0QC&46DP50SxcVs^C0E?F=1nWx4Sv7D(C;7Oz30kHs#MxG|Nt&rAW^(G~2-;jnucReCfPyM< z`s2s^P@?ValoRdb{Iz)4|5dH8$4>VT`KyQZG};2SR+lUf9Lk$^DS?iO<^i=le>TX> z-7%P^vs6>BndZgH2bFEgs=R*;IC+8_1`;iP!`G9FKhAu8WmYf$XI(WOtXHts@`Uvx z#b8!CZ?I1NzD-&pAvNI9M@}IDrG6SQvP>~(;!o#atnCXD-L_1p-(&>-cC%a9lzr_p zGJ*y43)^=H3Xc=nCQq`Z8%OahT@fl#`@$5+LEplCEqRbx?|-e|k?r&I{G74s`@B_) zq>Z}Rkp39WB%vjL&-NE^&+^`T zwPaP*LHuQ?q1B_L6rIrv_Aqw@tWAm}BZ|t4!5QV;4$e+G=GNsV4yFhrtG-Ef%Ec97 zpSJslvuN?j2pdKdUmD87=+(pf=wvEiV z$$DFqr}5C_tWM)(d7KYqR;sD>OvC(VlRTEgsQ8q^tYoJ)aYu@^bh4^KXHHnC#N8vD zcB-!QJjP^lLBCwR!DXyKLU^Yp!SL1Jq+NiFiC;(atzq)%W_PGtu-d=DD59rFu+<+a z>uzLPa^FIIAAzVthQ56I2E^CaLV-|{0|2dn+&7@~yVZoK2~zYLeohB{iVpB~eMEIe zG!MY}$@Wd4iN+4psx;^}iaLZq?!WWH#kj{vx4Om7b3^XN%cng|zPpv}BKc;GM31l= zFfo19^7t;`E!4%Xxf;nBK%lFO?8^;+GSk{1e&Qr!>5neeuL)x9?$w~?LBVHlk|?!= zg@o2OM3c|_XN~PxCR`DNL`Gi@S|;vF8rQ}!FvlF@#_o6DN&GZTa_-K=ktLih)ysbx z>P-+mmPypMoPQE!ah2l%kf-Ay>iEXS9P_G?Z0XJF<7uF59{t6I>&=F1x)?X@cROr# z8?#nIz@H>U)+NyBqh{8ATEDWJ7?yXI}t4TO|@;-9xdA2l;^FXwq{N7SReXS3cfV`JP zUUF8wE$=9kW5BHHWj2i}>cJ+jmfgD_LHlP7^h1|>Ru&ikt?i6kT(9?ep?;ZSyMIH0 z3z-;Rub^cDDW`ecRP@aZ=HA^JxT;;z^@RoO!}uI5u#XC-8z~d`POFJ3_Bzcaa##-) zgEe7gn$U{~6b&4&V1n%wS|Hj3gVI!fNgVI0%2apgUL07pPcAgDJB+6vC3qtV*M&9F zIL>68^luctit2J4B+)S{zimNyCYuhkh92RR=b9B6w zYZpHx2bOAdTrfMcXO2HuTrAHK)4rH1%#!QV5VyHqEkQnKoa8+|tMo1wz44YhIwHR~ zG;}dIn_Db?uo3T=IeJK%R#{64LmMJi)?JJ7;x#O_Y1aH+u4x;oB6X2rAyMUX2>P~r z>vx&UH|lad5$|z0g(Mhlst?$^p(kEAWPM;ODamoY(Qxr^g!MkhZL&1+{@aBE+vrGe ze17odLG4BULK6T6L-kqj(g1m9s(4!TaVVzu!k%{Q%z?DCB;`Li7QJ>J%X$ILVy^{m2M@rI8aRS1KPWl&e*am z+xMR{lhT$g!C<$F`-6!^AGaw?YVOC)LcF&18|>HfMT$LpDDWX%il((DI?wUCDf@ob zB>MyFBvUh4RQ@ZIdJ|&RB>dm?Lp}vXe^y#yBUd`tnnXFTC8LSVcOpwpu!Hd?H~-v; zhC3br5e|{3yo9cCjp(}g#kf=1ax@64r+np5=~wwQ>sL)8{4?@U%#UJCft6GIwX*i( z2)6#nNHV*%*84{*6HiwMJ)h8I6*mf4@(v{BZgoqZ>o~nm{j~$z?(BU2l>S#v)u%MI zuzX{qOc#Hw$ycS1jr)J7x;X;CkvWw4FNL`jZnpGTjc!N|XbyX_3b}Ly@L4jggdQncHg5c=a z>$u%>b?uzvQr^eTB96M>F}WDYyN`6y^ig?v1)M^I7rZj2Gbd(wn+e7;i5%RnDf`g0 zly(&{1uBk)juYZRJ*}p<>w^X*mi;O_mk9$rLLBWzVye7`{^#q5RAzZwWeLba(V<48 zgOt*E9rp-%a*wA;^o@&A50YBYTc0<7_VYv7>?Cv5kbHl6dFn5wyUEI5bn28>tgowr zzxvs&2~Fyk7PrZlt4}((7W-IM7Ubw)qKCZ%=H9JS_Iq^*Pw{Vt7Bdy8 z+~p;x`GQ$)bF!6cVRO~tAG4(r4F4P}>>v~yUV>!Bbrp+p?I*L3soEVJn@e7q=v&NL zuOEwJ+BO8nFnHtSTj#l6?n>ncc+UdcWR0InxhWgMfWN4Iz@^T>v&7G%nO4}d$i+Fl z1SwS1`SD0GPJMW`sb^pYnIGmXwSS{bVP;da%@?yPPxLEivZEax7yJXA z(;7-wE7*ik=H&x(4MlFcp?l5F<*(tpQeZuYQ|1}Av0JQ7J+x7VRhGY7;uPKr&ddb( zOBVGq;_F{2Ar*eh^pGi=``H9bE0&=Qkg7Y>atr`IJ1I9Z93bWg8B{*Ao4{nB0ZZ`o zqF+Fam0_t{K#7>}v0@4$3I=5r>}b1M=Y60%c5vWkTX28A^E>5M7#j^VQfQZt-`ZRR zN^26>4SY)w^fFXj2ekAg`|HUk(xp33-$s!}%fN9soM^4i05O~Z`3+>p!rMXTRp5+x zoUADIj>t3A89*HZw!03z-m&o6!9DIh(vTVVhL5+~x&CCbyjL#4MMHoG0R0!S9f9!5 zlHOC2zN*(1KF%fuFzto=SU|I{Ms$PGZ~x#jY}r(UZV!2HR|FZiZI_s>3AUjAu&kgL z()$%{ZK$tADiN`XjE{b}7Yi&>%v-dHjKT7<{50JjZXIURoKpYJ%=FcYzI>DRO^NPb zSEwV7>UuQOqXOba!ood8vPu7~*Q@u57YjZ0rrcZ5yEqhQ7QdWHg*I=cG+6RtW})+6`bFyD2t zgxKQ{_o&2@9VD@I;#f4Mye)vuD)o49vSWX(7#pv|dEK?>&8z~8yOUM=A*%~zkTZw@!@qZ zZhit#96Xf~@ytYDsMvx&K#uonueOQRGp6EJMsr(4@aT>heS>=zqPS4HoNm|T5MqK` zT9hiu%9NzmDkgeq;t_l~$E|YDq?EVq%iU#;jPCTQUv0SEa4*v<3D1e8T7Mm0w8dV1 zNUQr>i{K5v4F5f*y33MJ3aBf7$9x=T+-(Uawo}r7`AoU>qt|=q4l93fEJ{+z!{th( z`J^QXh^l=#=bD-er)$sNbh4wb28;URRGR|jl2O;AxRu?LcIW?fd)vLQ0tLLYwo6e* z0h<+JkSzlB`=qJPZc(Etpx89uonR?ylkU9hkU5+ye+OqpuX)eXHA9B^{aY1#5*mht5hgP5BjPFs8$w?rf2&zv8{Vbs05P-%5g>yIGcJ&0j&cJ(P`$ z=R7pObpZv)so5y0%k5Qsi2IRC+pMTX7G1?pNaPy0+-~4;p6VCpU zXQ=Y*URGS=zGzQa&#UJzHO7A*L`J-hIF{fRg@WUGRe!cgo_{!cN|lkD{O@7mc$hF9 z*nJ#lmC?HYsa@UkS4MU;{(qYG^l562!n6J+OYL9Jscc?3XeWO7>``__U#b)n@N@f6 zA^#s!T+#IY+rh<{Rj1ESRi(=yn;tgJ+6Vo@&pNxDYmPyg&M9YEZeM;TfBX$+}D$M_219vtm9*}RYhj`)`NNmO=@3>y}{tJmcu93a~_%6 zZDt(#g9%!VYHr5)kt!TIdhcR7H>_W-T&eX84~q2b4}JDz?OQMA^GT69Qa%})^Bv(e zaMOs0tclY5Ww_L9?NYz^SE`q5HPz}gvx(uca-+Dsz`LH^=hMuh`Q)fILzRr*xE6RR^+(kePAVe%EfS^NxBZT zSXyw2@x?$>g&!8b@A95>sj4^0FmWvZjx_OdLBkU%yk^^)G@V)h^N}x@RA-w}^?-jz zSs8BO^TVDIxANtY#sz~<40lRklm3Ri_ZO0zO|Tp$zkMjUrs@=^IQP=+jt!5CH!@8) zOM6nLkd+H1sh1*-gA4cv73xwyooU}P&G3io>X-b-M(jg-6dR|1QZA4p?FCqw8;bwz z&Btd}7E^wkndKg+bKs}bnA*jgSIKD{jIblY*_(I($4xq5_uI~2DbSkV)HGzdlGq=5 z_oPEo7HCOKO@IK%ev0-0{UDHo3IZtLV|Nd2H0c5Npu|;j;w#LVB+uJp!EInV0=15p zYH~E29WOgS*@PgeH|<*A^F$_@CN2;b5#)`bLrJnT6mJ+iRz;E*-I$}O?tUTo_1@;e zzc&v+pS~Ku!jqg@?^eBeGv-JH4aZ3)UF~VP%CfQ**|iW5heX&R2s$zYPmBXkYO}nw zzBj_?8s9b-Kk&M9-|eB<+fvXvtKc#;rL4BWc9apg{EsNR&z0sh6ryl@H#!+-xg#opdvN7DGNl_im%i5|kSc5-m` z_z11chD63|g=VM)P9*Ry?ogKT7{ZM>f~EpTB|n9K+Rc~%_mZCu6G6YY4S9h!9`|Ox zE&?7*>r%SeCiV-Rq(iQi#Ia3O;aC4cPsXJ8sIUZh)8U(Ywq|?VfWVb8&~enPC$|}YHm}sJZlEYP zn1-qLsU8+Fdb}pHP*gS4dhxi)Y4ML*@dGSECTJ%+bL@SFxZhiun=R5vqZ@6hYs8eG z7Gn;sU5a+hPr^-0=CZIf{-;#=VtSAYZ}743*B1+Ug~8$MQx@A_$hOy8OOHnmV~qkF z7Y_=F$Rsr0wL`Y6GH!G-uuUo?4>s&ZTE2=m>>FHPgXAm?8WvG`s-sQnx1Zr@tnV?c zh2RUkH}bm24Ec~dv<*Zl&8R53oA)TZ1Ej3Q_=SW(RU$>O^+v7`JEw(JU>xmsGQtxJCiT{|FA0wAonseV5Gwv# z04DVzGiotgr=XCi47YRV;xYZebVIO7326NVcel1#x7$8+Pe@2;j1?9<_g2RnX@5&y z?4vY`3jOpTil>gJ|A=NKPJV=j=>}fHtU6Y3dlPFX*KBeAz8CK?G&8x?C~XYw%(f*X zTg%`;V!KNkN@c~KXZ&;?C~Ya={KVYIEH7OWmKbSH&!%ry$Rrj02Fk!RAF%(6?2$b6 zLBwE?n|+LWXKg};ZjoBt8cr}jkG1JcEQNT01Dx|Yf3R+?#?fN=4x;slQ@ zMOF4BnHL{MRcOtiIrZz|F^1;(J)D&~=Xl?Cy;H&wIMwk~tZ-;gsLJ*rB~Up+$KxpB z*W>-FNZq^bG7BjI1qB~Dq*wq)0W>5k1M9YR#%=o5z?gW4uJ{mMT@?XMd^R^{XPNjBImNH z>uCAbNDn;vko%f~JYi$#L!jICh#E4~@9|^1@E56fEKxw0#cYLV5o8;~7V+6t3ikIw zDu!?IWc^eMsNK&*!}!T(;&S8KBxEapB%Me7eMGD8H3aI>n=loJ)GxiCQcqpU$bA^x zGKyX?^t8+SAa6CF8bHF2tfyAn8cY3V=-~fLpq4nDZSG^Z5Re@3yG=5Va4`4ZA-6#b zL*Kc3hN4A_%p-O&Zo^_4Ht(#O!>D+3tum*%O@aj#%F;aFYJmt|E?)h%g{kyI)`3?R zzhS>9RE8`{l3`C2*w#2-ahd+6%6oM-|FmbQ_QotecX~{OUrm$XLIejNOMPd z%01By&^6(wYj8(PS0GMw?$t>Z>qGRRk!>& z!=VKGiLKu2nA>G>eyk#9gU71@SJYZOfj2bQozbSv>bvSp%~#AK$()_HCy}#YeU}|K z=E?$Vd9Ra9M>{%wD=Fp*Q&Llt$*STW`$?}!7egiIhEzw1jPQkxa&w0nBnGxM`zjm( z7D5j>&6O0UFGWyt%c|L=H5?bew~9qic@-}QskRrGsyj9lUV2fwu4dDUoD>J?0ycgd zPmj-LR}3#Sac?pnm!T2U)=1FThV8qz)~_tIN@^7ROc)Ic;6I*Igg|m%HW5CfJt&_rTB5$yN z=gre0BEF&cl&KIhC@C}yD1GlVn*>S(=oEqyLqAKt13i64hW*HV??>p_uC4sjrH7ak z^nE>oAwakm;Ri;Lmb@xixu9e}VbOla{cl}&o{AEGlII*1a9(F16J+5HVj6pG1^SY! zAxn99H&N+}+h?-y_QY!G{Luv*b1t8+eOxRdW{WUoXlu@tNZh{SnnmTO%qNA z1BizkfMjbn=k7&I4gKI>&F4XcK>j9Y55r=sp?r$q2Z+W^lox1gT=P2>UfQO_PT_7N z{8Kbm-xUsRuswy9E&S+&ZTnuoZJOHMR>;oeD0zk7an3Mf_nO4#gWYIic(W@IqB#LX zMBHSL#BXPI{Rt6z&LDV|73Q~iR@Qc0-mWDOE7vWo+q@T@I@^X+n+o--RLB06*TnlY zzg3_(TAkkWzRPNo|Lu`ve--XM+#~9e(mBF7(Oy1^G%oc)`xLepwjZ-|99a-47QH;U zK8eCk8E@Za^Tw^QlzQEWdBih5aTIZg34AfE{o&tSd{v(2=$4pNvU?lPIRfOlRc!0I zmFKziK-DWqk&{Ot57egQ!BZ8RKkZ38npOJF;&%;-U&*8L-1hqFtD%`!43yd;h$H*! z=}<#ira_dhrV8(sQ5tVnE^)QQv3fIZHx{i&9q^MVPBSy8e|A5;4W63qr`@olUFOKo zb8`**Fp`;jgvl-D@{B>zJkDM7_$d|QAwPB zQNwVNv-i+6dqa*w)t8;j4F>xNC2CsrFK&AnDd$22 z!guGAo+7bKtG^~nztQPW&0u7_xlY+9t(R+p3t>1SIsUB=B_6H>maGD-7^*XxV7Dy^f4jSBVE}p@&4r z0jeXfbUrwQM2DNPUU;Ole23wj@;}bLCEX<3=4W%O6nEc0pb91zyx51|4>)86BFCaM zRrNh}az3oYIqCd-7Hn3rV&zUjmw*x6c?5&=33%;HD&!APVGQ-|Xs|zbhSTLXp1tj1 z&*K!AezUA?*EI8X9DWC$|DVB;f~NA{r#U6S(G%y+_##tR(?W&6(%kot9fP#eDY@0O z#&X_%y_5fn>xKE_MHA+ z97#+Q%XfBi&(s=%n7p!iM903VzVp8RZtzi2qvO(9L+*Fv?m0J)oa$&VMJj|%%sR?> zp3Bg`-yPo`SAD5pvi0RT@Q89&Z+R&(Ym0u>eEb;Ua2YCIq|yu90RY8#sWs**eq=mLT@gI?7cY$a7(APr_ymxFS@@88RYCjuVvl!gUD~vTtaU_ zpd5X|KPh}ia-(JhJYg_c>Ci0hcrj@*o*OpIP_jU8L{#}Fr%P3cy+ zr12d-@hg1>)6jlg^dIxUmtrFWG9qE|)lcJSZ?~bnB;?e8-=)A;%bCp=!Xj@5_uVET zGVq;hX_55Zv>$ku-VQbfO9Jj_5mto&jsdK)WSVr5uZ=HbgyCeCclSeshyeVF5jzPz z{09-L)5f+L>w=?v8N^|J9nr`004>?qnrRQGftDXIl0$Edc|l9z1q>P-XRUx5z*pa3 zfDsgOZ`p3dDsxcW4J3v8F-S!Ht?RxhG2^H4$khhIZwmgfihoI)kAD!At@ypQdc-X! zxb=xXgzcHhR|JLVJBgxjpbu1jZIwXj;+t^pO!(&~+W=R)uIQMU`|1kJ3_HaB$NSk- z9sQxohzCpI$dxGGwypRAz!xKdm4~4%00>lN$ljRc$BjJX$LnHtYdA3ZvbdrYW?lkI*Evy=H;nQj!P<{( zv+q5aQpRQuAC0xCJ~Q5)SX9|ChV~2K>)J?gH@}<bJ8b@?ooe!E5Pl=!9SdyiqX0OUi~_W=e)vM$;J7 zV#zUn|1uLyuQJtAc72i0>VJ_&#Tm4xa=jW?XvUa~CPZaQ?>Ay%&~HiuUoi&DyGThh zAUr^}4jRks$K;KxREZ@oPyDavJYLi^F$(!De+#m+CF3zUBFnsL)u5NelmvX19h^gf zyq6{XH_}Qy<@WCeUWCikb;NQ=?rH?$&KJd<+iaPd6phEH>_=<8-M?IA#%EsE?EP6{ zFu9!EG!rm42Qk6j9Fa$sDqNwrboK4@8w?Ytrn;W^mhtPop(@eyQWA>vv|@}5iJi@e z%Wd<2oumIx>WfRqj2iGRpzLV*%gMaA}uW>nCpHm+e@b!KYkM`eRuPNfGURDYk_9z%6eRdK#P$CBvQYxq5-4t9x z9ER=&5ds)BH6AVZ9Cd(>dwgo*x+U0M@z)dh2ep+o%?Oc$lou_pd>woI?ving%@S?& z%)9{IOIXr0{KebH_P7iiXG7lmG|lM69KR*k|6%JagW3$Vt(`zA1q!sK1&UML3KVyD zm!QQ;DH_}Y1ZZ)mxVyUrcP;J~+}+*3oHO&y+_`iAX6F5qWZpe{?X{jYFZ10a>amhF zIH(p)RUELrW)$aIViZ6Tay#b@IVx79uwtYbAq3YL7-d#o6BFbIp1LM$_3R^))@zDn z+M#1r%jij$Y%>MUJo;7Y;BRUwOJ`khhRkZ`L-9njZQmBc?fE9kIqFuU zd0Fk4oXtBylUF8YcAYJ6>eZDx$um~=;l8^r z&wwtS0u&VI7pp(1f71@-!Ct3NC)^2r-H%s>%L^-znc{aRFc$1v{~`WoIS~>hTEmlE zWjJc>dqi&28gE$l}0MZ>4rBPWB#elLSwsD}ZW3J<`M&J2Iu7>zW_d_UXvZ6Sg|= zp6t>3G;Q?;sg%z!1NH68UHZ#>D)KM@+RhA@cK@xhi6)Osk{R2}>tgl<1Zr;_U!=b@ z7gJD|2=fS&Z&#YZ$36E&-Mrs9WeRyqUm_o6Et0<6_F;W_e!gjQ@eboSe!enzneO0W z|0p1R01Fa0S`)N=i`YB8Gf8rCNO}4a|1Gy%AARH5%OE}28kbCQ8Pi|S0QHdoq;>8I zn1pIBZkh64yn_-Je(1>I_tkVETP@mP7gXlAhGJvKjHh>J+nA#73D`<4NQc-eK9dZI z1rFkWA-VB62y_V(%oO@J$`E4T&|9gAUH13wdD3RGqBzZ6z*669z1_>tcRBC&? zv#EJuP}+Y*dBRm5K-2c(yMNSoh9mR<(+BK7ZNCQ(K%0JGylC8RbDu`@nhY6a zdQm2ia_uKoZy)q}xqZ(sbyplP8Tu$!C-nM4F`c`JLMm;tZJ8)5gYY>bO~AhUo-Ts|awyd@z{f0d^Rj`1!0~F{ zFYp<2)LF?3rJF!r82-1Rzcb)NG?(z-$^C($$$=^iju{SOEw*xpPGB7|w25P>rR%4x zTFa!H?YYqv2ew(GP3O<=I15tK3loKZO87r*RZ7N78rSVP&Tkd?s^OVw6=RE_1|5U@Ft5q70jF*EoF@+*=5a;kT^Y;wm5y4{5ZWAU}^oD zVrla+;y(At$<(&#R@!AauTc14N8Wq-MTW7H1k&8dLL=DvyemgJQh&DJ})KJV!k}x_i@` z#d_?Wth}6RR*&3}wCzDx!$FW|F6Hf((q(`AyK-)WlJzH6XCekKRbh`HK!tKo4_ur! zPDVAGr&)VLgV8$jCfTVObQzvF2XE!7YY_Q z7YnG0@fi4oSUg)0;eRMg&_)95(hNsYqrX15)Jzj(QfI-?M6|hYbqqo!aD{RIGXp(+ zj?|o;%f0W_=is_2gf$rG4U6rYeO7h9$VkO5=*cPULExD&sizfu5GcMfe{?yumGaji znoHan{%}v&G*(fm(?35hO>IvE3$W2dIqcv8)aEICMd&}RKAYX^RvbNzg0tM%%c&WV z|zB}c^;Q!Z<`u&+&O$@bQWfb^_|iFD$`$e=nrizqh$-o(YNR~Vui!!M+e z*fB4gnqK&k56j)XUiYQEvPcE=DON*2AJzhb=@MK%Cktl$X%?NmDUson;j50{0jVL zr~DK1;-JrY^Eny?X@)QA6*nTs#^wD*pW7&hoVl~vg$;`84G07%yh}Sk_%ks9K8Z}0 zEx>&Y)N}wO0IUlg_Gf_KW<(_F5#V_2wWsmFfX7>6a?%X^jJFE4eI)KfrHQEO*~^S* zujP?XBbVJhfuj7Q!ldU}Bxym6c@=H<)8#3>q}$!TFPk(%c2B^$FU;`YlB73Df)qkz zgn2MC)~aU`Fw(@5*UJ;u+pLCLg!{5ngtvxhkMI7YZNN3D(J6tvPoWSLTljLw-n{9? zT@L!5j3y~EX0*i=yFIH7zc2K2FZ#^_q46cn6-_Hm3Qj!hD%uW!LzsYU)W@mYREeOB zExi8NyaQsC_L>5sLb~oA8GipRo?qr*I>2^-DztSQ|15l-VpFLN2OBu#W^~x{AZwsJ zJKNcOhd1Zo(s76Qm6nOU6cTQhY&`T=?)KZ-SQAj&9h8sSe{0VELvDWmEXg&RGBepr zK|0#+XZq(rgr9jub9RFdD%^)fEKtqA=rFOiaewRDf{tryIRYs}hjISQwVBCh>Z}yo z4b#5gARTXs|2oCDP7%{wqYyi69<0->B;>yQB}4K0$xhGC`1i!l5NK#&o0eWcPFL_u zUHJ1!P%7LWRE7%=kiRy$fn#rm$%g9Wr}G0VsyBr^)w!Baz76wug)g(3{>F`A(!A(W z+PjInjooM;HqgBr-M_?%C_XCtk?T8B8D86%hEsYzcsxtv=_1=EmV5lr(#W!l1%0jy zKvXh(XmRi?*uK>;A6euHPL3`P`C5m1c{_SJ(NVsCa?+wtC*t6EoKk&AvHvaB`7uO! zl`p&a#-O!DaELF<#yZ3)<5!+I*!40LadCfo?7AstKV-!43iuKa9`EyFlRJN|v;JRq zHQ%e^Tf_CP*a({;t7zj%_NBVMj^-c|_N{B~#Qmkh@o+Q+CxwH|@c>x1X}+Y@L~}L* z7vS%*>%(_riAL?lDKk3UuPTzMz{ob4;*TBuJLS@f=_|cjoRA)Ail=aNi?Ky@|NgSf zkZB(W4|^_gHXr+(K*8Q$b3}G+-^X33KyRZd1#p(vm&Y!^vn6<%P|~cAkRqef%yG6# zym^>(q8Q@8s(EQfNV-382(a%{Q!f&hU5pP=qA9$kCi;!N*8VE$zzpkDMWOY3{wSLR z-a!)L&H&@$C^*c5>3G}`=-nPaAWBo4VCw@2X>#Aa<{rM_G~Q%0p361&4CkxakGiqk z+COky+h<78SVriR6YC*gHSYZI3O%O%fEk(^IVtN_pW;5z*3tHvZ|CMwGw^W8BzX4b zQ!#Kd$y8o5@MA{lQF8rhF!et>1C=xlPXx>u=@66rNp}-Qi2na z7SR0e7HBUG|AM}=h^~oz zBk?ML4-E@VP0KZB>objkYSjm|$r!5}hOS=a*0AdJtlWV?X1jy@OuEnUt97k1%8ue$ zKmLHLpq?>*z6MToqO74;wW4G8BnroPjGxKYc)r!eU!Uod8ws7|J0cV)WKq1aZc=k8 zZxhqL1NL!;8uXUjVEy>c_80klsX9-`2@_gWvabR|GsH{?_@yrg4uKQ$PR-0^{xTI@ zC~eHspI+cA%tZSxg3Z-*o$7Q59}wWG z;+Z5taQSC-V{qMMR98u@xkGsp=T)&$R|WxRc!AxZZ;|CaNN>S-)I4DS06DMK>@_E+ zmH?q7qV_1O(TxF_ZJ|hn1H4q07balAYDeIm;V8=HpIg z3dco)BO-%3)&+bG=O7v4+c|V;M!#U8LfIbnb+Y-mJ^ayoHvI#3D1>Fyhvv;r+PmW* zyzLI*>zJ+Sj=^MGvbPW*8-SGLEzlPr49Xl~1v2gj(hQfYY0WltGk__8aMUWH@jUsDb6P&8RO;AUaY6)F z3gEu_8#U!Mnce)wTQ%%`$(3>a6PIAv!Pln4Z>XQlQI{RxpCc8hFi!w30Kx6j-k%`I z1>TZ1D5$vHgY7?YrBRi;F<8KPX;au2IvFGfcfbc))Fa7Jb$kW>{RjvX9I`ohLhZFE ze(`=+1|J#}_oY3|eYd69+bt9-Omeg0GjRBsc`DYfoy3R{0*DYeGD?9|gc`#SJ9w^h z5(^XiTGk2rzTd2-p{~*f90Y0#I#CF=vHGfTb)r#V?u1%SDB~J^-bozLRT z@O!>jnPv*{ZV2!5rO4Av75OZVR9f{TcVu{~ptTWmC#qAZcUORN;ABv=&?H7TkF&B8 z(rtLk#QP_>9-rH7LMrJLc~dxYD20@M&FkNHX_Mv*tG=G$u_Y}j+@6X;D94$h(raac z%zV+>E$4p}>pK~5a}D5E`9vT2&?{Z`v5)%@EEbN0P|B31T z?2kI11yAbAoMT|9D}NlzkyBDoGjcBTZ>qB_$d>XsS{mX1_glG1$b+5j_i9RweB-#h zp^<}pd_q0Tn&CGYkJ%HHyT)~ax&t^uwC%rIaJ*uQZ9MdMhiy&}I$ZB$=PYoG;xX^)GTxAUc+cR^Zm>eKm3EKVQV6RARsY?4bV0uFB0I@L7u10w!B}-@zkb$yps>oqi_ZF& zLF?x$$uqWF$ND)rDeI%V=U_aevvG_}vir^4tHjEq=K{k{$b1xoy7p48e=j))2fVx4 zSYCmHxTx5w0_wwius}Q{#x~*unGS0y0`EHfD$`TI**8m5cAu=*N$#EcF)?K|!CUq^ zdV5A>TD_*w+Bj9GSa%9OK{YdNS$Lr0qL7|cq%&O)LnwOi=_;7!a5Cytg`G4kSrSy| zB&$o03i=%|*SM@X?9Pf}T}-Hg5dZcq9;OUW`t#uAJ8yiPE|Ti5b@g#g7b+Ty>WWLV z)P@(5rd3T;Ew?~*d%WBp3hMdr{=m}*QNL@Gaw)IC5nN{CJAw^Faar^c6rhaDBIEasFF($|2Y z(Z_B1q6mIVY+6+DVTm{L+nw9aG*jwD@0Ov^k6S`~-FoT9ItERtcQ<&ic8I)zuYjtjR#AxVXnDwgXuGSZM_-sH zkT}PdfAAwK0GMh54lc3n{t=!cr6A=1TgRxo-oJtynT=+iy|zMf1YV8(xZq#(+-6I+ zL-d1d4-XH2eT&Jp`ia2$kX2U#_y%7B>dnNjCM-tAb7C+8IWFj`YkLCcQ%OTeGP({J zoRG@SnmSLgM;RbM=)ZVQWavL^TC{h@#QdxH+jW}}5QcYQycZsmp6n}Q^f}DHq)R-b z@2FWut%Go9vjY_xA`pPG5O0JH;J!#oMy(U%O*OEd@Cb;RO06*?nJ6ck9OZ5W_;xA* z^31MO@bEYL3X{l1S4LPab}urHbhFhiIOQ`7{X5&{Z3~tzOQd`N)*is!63*tPL&NBmMKq4{byPUSt1Q}0o8=!~$>K&n z6BeH0)4!utf2rRgspG zG>(Fgo2y|2Tk?_sdnxwOeEAVEu@20>@WF7y=WV@j9{$!V>ivXiBYGVx(japztxC_4 zRl_!FYAJU1W<9mZYyy%!CmlCLxLOOUw?I55<{sv@v$NBP-8NghQ%bGPGmo`BE~IU~ zM-OYAXA{irZzacsx$u=D37R!1dR&tfY$Ws}+D66$%)XDUbYGO2GL6gx7nhHpGpv-K z4_Z$aSt6v6Pw|acqj3fvu&Ti_<&mn87*m|wbwnccPYpo%t%lHV9 z0}8cPn7*LIU3i*Nypc z{?#$VNm!+o@E2!br&L`t8V?Q)bWp}#y9FIJyjz!`Wu$z3JJh5t(!tq}rkk@`ffD>i zui&3@@<%@eii&+10ncEg{K7s=De;~>C>Z^Wj+e4mq&Z=gMFQ0i?#oz_M$8g{_A&D7 zK({U%Gw(dLnP>95UR|D6zu?+hamh?pqrHaXYL5-@H$uXl^Y))J3cZXGr!2+sFr1*b z!Rp;vZ~P{oQGjTvq{jXW3wQ|-HQf(OQ9Fs7`!{Lk=dm~^E~Zm=A^ZC<09 zx!WiZN4%HO-R9e{mZCJBvIHo9vZ}b~P+eE8&7zjGptY!DnN824)Y^H3g{8W*@I)D8 zTvtR;n_PjV-rJQU#Y2s;P zi{b=jV?6`IVS$+y!~n7^mANX=OIOxBig7!5&G-_IKrhmb;W8}vKy-_wh~8P1?}B<@ zS32+jFO5FZByc$l^V94!cL9rM(Uk|0-GoaMSBHFD**4r*0A~p9Qj%*Q+r?>TGy9v> z9-Q`9NSCW{dDk1AOplCLWWEC4zNR=@Yd{PD>DB}_GqW%TfsHUudkCs{Gv~W>fx9z# zquStpMlUjeYNj9Nt>^(Jz;70mL1Nht+yW?@%>%OmzY|t|{0N?>g=D6_ej|Pn=Habr zHhK0H#q&%a_^SYK6n6)}D@?pc>h)*`Jv1hr+!4ItK}FYg!9s-S@RH0Qk0Y@UR@`)c zq`3b|Xy>eXlSn$5#thw)Yuw9AUgU+Eebo1Qx>AgeydTrd$!2!#b63U?e#MQn4Sn1o zb;xFubH9h!W<% zk7z}9K7Tu=SrZ{dKjyjLbGw#i{{m21v{_fh>&4gz;3gSE&SKRlz*8RaaX&2N5+3m} zNt+>ZzxVY-in3FD*rf=6kDXJwLja~`GI2MKx4n+ph?Ns4;M=lKwd}r`fLvYqI;`C2sLN(`ZGd&;uFP?u{DQliL89tMysmu&*xU4;_Jmt0Cq?YeDML_q;(f`Zoy(}&F zA_rXXk6r7mZkw;X50@lfRztLNT&Ax>ghv+m0Xrf**S4i%0g8>V)e3K_*O~^N{pWQ) z8ztDLsQR_25v?W2efrLO`qW?06nXxb1OzO-pepM8BqQh{eE=EmacgceBX8#mm*FYS zRrXw*vlvOWex-kDvDcv~oD6j%hJ|7uB$(J~1$bNcrPqwbJFQ>7Cx&^Fr7;i|ITI~4 zsfCk9&6sZ!R~lL}Y&~*S*1lYW5kNz0FYEuA346YILrUcFNba$DYS)Pxm`~i(7ja`G z>LK{$ZkHS@dS-U}W;X86xkqkZeqo7Wp(JnK)!5uhQSmS7hhEYd*O!><@RM=rn}WQD ze3+$S9l{2WP_dR%tTOzoSoZ!Je}y(J%X zYb>+WHYgNy8juvyUL^rfb9)a_Vk!7p^%~Mn9*-z|5a)nf989)IR; zQF61%vY$t8UYb$mNz#&2sh=fwoKu(^Ig=O}uTXnGbLZY4884gu0L#c3O~hE>Bz&Yw zs!-IAf*#VCQql`9oy_!KR|#!r6(%T4d*&%eFe)13!QuQ1>W6NJ>!Q2 zUFP!E`A)(G82G|lCclUQvFWUogvV)caG|7_MM_CrIfJI(7Ua!L%!U?JT8Jtv$a6*% z+D#@LuT10wH-61uoAvhz_cwygC>7>f*Ckn87q!?=$XHI-Cou#}Yw;LPlyC1N?qk>m z#vuX+pHiJ$L=`-cJh#t*`KZMwgXa!1{u^EoaTTvs+d zGaT0FpyyKyE}hH^1Hr2rWG#<%PvW#~;R!O=4>4-{)Z;wb4OsgorZfi&5zy<=&gMkJ z5ghC}U|YiG3o8(5$k&GCjTkre+kXJsHT+0_*IDlm-B+EzkOY*P+4WlkQ4x18fzvf} z7D&5~!@y1ozge`V)cQp-)*P_+l*o1KZ~3hAbvxebM;+UCR>Swyc}o0ezR2q^k1+%ia$97=#L8)00$+;9FNxdN+fWkm$M1wC9&^+cb%zouO1i9Y)K zzeYU)m5nSzn!et< zle=@ch+8kF@aPk8vw6;#~wbk>D=(cGp;wBt9vFK0o%V-4H5EG>G~5CFbX5 zUW4CAwWwBUimfV@od>q6U_91M1Z?R zjPJF7jg6})c6bKjlgd=M0DIvNLp{mxI413VZw(DB>e!%TE$oWJ{G>*~jF1bC`ZI2lsJ}XB$8zBUVO|4} zwk#$$6i(-= z!)z{wX-GH|6SE2e_F<16%<-*NjN=MiRA8YAaw_L-qJep;g(WRCO)XCv;Up>^xf{0e zktE@(j0aNR%}a#Dwzm_-_=}1O=c50UgQSQ3NmS((UG51`DqhU z#B4^WRx$TdYM2*t(n-tMMpt)>CsQU+QqweCT>{+D%w^8=@3!PZVud*1Xb1Z!@^(jV zlFh2$N*^yN^DFz{u4t8OvVj<}LT(+OBe@J%|0Z}LU09ueu!zoEHA|-K;Rf@~K)Ny| z%u1Bj&OH4dtbS~f5oXx@#bF=$QG~9!;$Jzw8*dPZ+An&UvKx&FL!Sd zkNiyK?g5{#+#Gc*>bMS5-K+SX8CJW{4YVG$|%U*tRL7$cpJ&B`L=oNI4^%5&m4 z4r_*kqxaN^6tzf6vCFSvVR(Cz`^fjipr4TnT6n&^2?2%Hfjwv#81hpswcW3@1;n7i z5vTolsTuXVh-S-tM3a|hr5%cOb9@Z$TsONca&CZKfsI_<{+=ls-}#j#TVM(gPW^@XOgyuy`fM8$r?+w0!8!9N|?zvMRtRN9N>lGJf@~25BSfC(z@9iC)FcraKe&C zjdqHL+-zYISi{;R0@)4psl{Rro)0eOD*Od$vA!u+QM2=@#a+tpz?ikXKj#D+=;S_c zIqhqGFD}~(E24vE;fCm{)M)E!EM+%FNFNyYw^H;E{Bv`0o9>LULcfRL=i z2Th+FsRUUcKn5Tpp*24FjpJ+I{Mg_>G_-=lY;cm|_BXEia~nU+CWf?8v-?(cKGC|d z;6bbyw-d7CsUQV*+51uC#1ysHD`>*+0BCSMZ=O}cRg9AoS0j`WyYNINTZ~Oc_bt;4c>DUC)pSnD}6Mu}10B=!)1vF8JQKBKZRU?6QsQ38g{L zw*-Wn#?O%@Cpc?9d0l3cHe6Tdys|6ggUSo=lWn!|{e}P(;Mi|-!^}2~iiYkXv^qd^ zG~`|2Qy}u&t%cABY5eUDkLq!oc0u?-$Jb*vT+HTjGvu4NgPMMvUKTq6vVd31ZC>2e zVK;>Btl%~LGq?mdSnSsGd_qm>nC51dkNWG?mgjp(!A%h;fBnvu0*OAv*L}~N!YN;2 zD)rl4+||AaKlV0|{cZyTx|&uD0WzuoTwcW3gjAz!pB>+l`avRpbziU#3g7zpgsAb_ zttSZZ-_#p#zWHi6N>mLYaC>{6xLsFbXHQVdNjwW295r7cM${A5mb zshW0&)KqNvpz1z)M~cYDv?h_cpU%#M)V^ZZNiLmrIo}z!BZ$X?yg_axXIR>4ahqh* zLTBQ_Y7wVhaq&ISek_AAHC~T%Z?+&D?YQnzN@zZCH5}+G9jk! zNuIQkRJgL^OaDpX&@sS5AiCE{HKF=n{UvU?8r!XLzQ(l7DK;1kL3pgFr1oS! z&s_J6I9OVHhCeV^E4r1r>A0tA3Sc!+t2SL9YN*L&`_uT>Kyx%P^}_b?_cc_l^MWatA?Gu8HSzrA%_@v3gdd8-6os%|B5uC#pAM z<38orglgsH%u9J$B&)8AiF{Kn&p)R?? z{Y(N-H2X^~67sboXz+`l|3XebHQmTViGuo<@wku>Rq>Bx!_+FyBWGZj#p8ARa2ZQ^ z(S%2tacez4ujAD_3{jA z!Vb~~AjBv{OU^tKC*zlND-@BpXI|?blGAsG!Qh%BY zMYKg);>3jgfe*KyUcpTTiTBW-ag`PF@TM5Yh$nHG^dUhIKNf{R@j;ea&iJY zx9D+TE)`iGsTt3DC%M0#np)Ud&l=X$YtXxz?oxax%d=391uf{cE)X=qU?b;6d-fF- ztwvhIVa6kTVB@0#-N~{{BUPp=zNvb!DhFYndbMYH(X3F(fD@_4^t}}0Aw|*BZQwqa zr?k@niTV@#$wI4XR_0*_VP5CW+6FHbt-uT6Od9D-$VG@I9=Il-$k^*`zEt2dPPDx^3#d^;3m8NY6Tooh)=x8Ovn zUACM+H<C zH1^F?E2&Ay(A7Yl0Oy1Wq`Wc54FbzWBZ81SrVQ+89RPwtH7anEQvKmoPG*oK6w-Q2 zoK@DGZAJAyuu0+Ekby^${TxBI+B zh`wj+1qA4DmLVtJZqQr-U#V~b-al=dLxJ;Vd``eOS=xPYXRE1CVZ4T9ozP5@!+zAY z)(jA80x~7irWv8_J50$KJ1v5+*5ln>+g~G>6lZ{vM_~Ahb$A2UR3a-QFjZolz&t zZPt}1(f|mcIWe!At6YQ|631mC2g8&DK_!V2L+)dx?2kUYcR%H$f6pZZ|$F=x~5ov*h zjY$^yoL1}8gx&*ud7Y&Dl+x`@_BPRoE9f8R6c_Kzi@Dx?X(zYJCRR!yntDIjr#lnw zA*_t0Heof`1>0ni4+kBG*VmU2xSoF8uFZFR95ZSWZtV--ryATu;}f)kzMe&QUFi|O zDXn~BO_0(>fcsAieUzHc)>FJwYQiDMQoLZk(VE0(;Hm)j2H&q#*GFtiMg)9!I8250 zzq9Q5MeTNOl_EZfhLqGJ63Mz5TSGA8Zr4aD;f8gPhxB)O{EmTIu&hH&ybY;BqBi|7 z!}L^p&iz8I<<6KdNz!uZlUfr82X`Jcx`};iI)BM{@|f5AB$F81thr6o>tW2t&DLI( z@8LDa{8IVZu?W=lrYmWea1xnMFvmIhUHm6zSVRYVrJ}xuWG(Ij#B0af`TBUG%b0XZ zeKv>Motk}uqu^|roWV<8FN}%6(ptq!FU%SHQY%s8INZp@6lF%MYv}R{e)%gZG?cMv zmg-n60Zm0i@|Un0E1#6y-~jCByecY>oiDJPOwnHT&&BIdZ6*TKJ3r3w0gRZ$_)N;= z?>q4^mV18jmSPgo*19XJKaD}<*7xndn6y1%oZwPTDbw=glDBWKioJ4_mYz~A4$Q~q z!hsylGqi#nk{v1{BYbq>AI46DF|Ybb(=xjMQSOX$Q;_Q>Qt<#W5hdA7+Ks9W5D9ul zCN)X@xN}@Q+H6`mbCf--?cA+fM9y|JwA$?={z0pU264Bd6BXRCG`)g>P=~xzEf6r z(ci$Te}5dIm9+Tc>Zs=^sE?G01#BnzXmfU)QLBnzj3>QOv3-+-Za1>X`Gr^HFQPZq zvjMj2;aT^KG_S611sWl$J^FPS@6Cl2J#PoKk!LbXj|6W5?r-DJF$lW0W2>moHoevO zcR%KOVWSI$?P1NpShTUOq3OgWf26I>B@!mS=Ho9!#@7VzKOY$CzshSiHPm-h*Akv& zp_~iy@i!{T$IGD=)*tfllNz1;Q-JaDBTSh5FEF3DBs;*_@b(MNObdoi!I(tgG$d2u zo3;?P7S{^3$HfPix@&}mXSik-A5#aHjD#mbLG9V(u;FaaN^f+VW9K-pj?;{ATtHn*>3nq5(nSHEUy zS)Ki?nHp6};}M+SJzSW5>tI ze+9UDQ_Li85VzW_2%^qt34N+~O=-MPVboQu14;PTiQ}y#Og9tqu#VTZD{ouahT43K z3v4_cUjO~2W^k-lY!X|6zj+@Cs4W!HQfJL@cgi@S0T)fTCk04(jIN5{(cp2Lhz^F` zL+*??Lu-lP5O1>9-vuF>sAS|%lBAQb*>PCIB*Y?M$F|}k>A;@n+OJkb?3+`aw?UM8)Nwr{%T z65N;X8V!#TDtL2SEpq5ANA*?BfxhQwN($7exo}ccht!E$u8 zklzmN2Eyv)=x%nQ=6qDNaNy*1v69T6H4N^8&n*_;lo3w0zzk;eoUjjqA7~uahQ%89 zm-S2CX7$|ePG!KPMB^RVG(_U|FRA>6rr|>6@k-iHhHt3b>Q>Ven;prN(~5iEv%u+4 z4ZJTzqCKeEdCNK{`Ho5bh84vh1c z_|85YQp&@-)79*_2ok|0mdvx64{H>G5dwnW(E1qturp@|FUsi>z~?Hk`jYQ^GUjlB z2DM4C4L4hh`0G^>XG3ucsM!4}GU*fvhGiLeYM@6h)|k}598t?Yq#kx-Guv8;c0__d zO~H3<*=Vz9ejRohZn?AS1LrxY@z?j1eAuc0Q0kIy?p$Kz-cyEnt*Fvx%m0@t@`cu6jlw-Tys>neQcXl54HAM}C`h zh)Iph?o9cTUzre}c2YB>#m3AI=(@Z{2^h;EYkpt}YYpJE~Tv)M!J1IOnZiL#&k*grLMN*9~ zASUHQ{#b=yaCnfzn9155Il3U1=-Q4HgPTY@`!^oA;MC-YSS!*AvzAY|vGvzKckt>f zhO)lr;{K$gVpfph36d3|7^UP$b%I(&#p37t=D6NP{}?qZ_oE}{5f73Pk(I4PtB{fX z5g3Kj6`S(z$WT8E;pDhTnaklGr+!1->Z^s*{7m%^FP+{%KF?#kA^19%b|l?s);^`X z&lLWXwgX5x;~f%M6*Ter4tc06n=INXIfXeCLBlu|Z4>p0`a}{{6lfb=pe`YqPtORa z4l?C$mh8TFJV?Evee(|&r~Dsx+m{cAbEJjR=?c9bMv4sKPWzpIMm7IsIS>zF=()Cb zZjU;#Fnc^Bp^l9CVqkUn21{JCx}X!G4w;PC8=m8CH4piVi!%&S%dS=8`d^bCtV{Uw zCg2(4R2EbyOZdJrBstiS5NA?$-9$kTNhrSi>i}c_0#v{ z?<46hl2%nbUVnoWB$?mLJT{Ogxp)?Qb(N~vPW|NgdRx2EMQ3RgQ>8!;yA_atH#U-7 zn29$wf#Fg`%P2{nfZTWc2`4#YE`hQ~JO_bMR;VQ3JMY*SkqCxS#~fEaTh}e&9E0|Hpqbx=E4$d7gf;Y-jMP8a8`lx;u1}; zlh3|IvihiwD_GBBcd@K-L~y$Hrnt3QcUr;A8xj`V1a1?%0&Q3n5Nbd#6sI|kRH0pp z9PDt|Jv44bA7r(ZsX$1r-ZZ@qPE}p6{#>S~1>m)#w@m`LvGI|<*7sJL@?spWa;4uA;RJkZIF6M{1<-gP z15QqB(d&`9f#;qN3oGyx5kbAl>Fzs(7to%{4jX0y~cyQOp@=t}^a|h!$wRFo_gZk4*|v zyCc)C$Ao%eN^Fn6@%f)61p$@$tA*^M9B$CbC z?{Q!<<{SCc-;kB3>uej6gquzbpx!r|jcvBwlll$Lh4M-F758j~K#n|F`c;<2WZpJ`)qjqwWP*x_kmuiI24W>YG`YwXbj}6|v#ami=qFd6s zv0IvdGG7|M3>^6SoA~|zcsdKeCjYqWg9D}_Ohvj>lxr+?~q2x#|+C*=HBcJfpY|10mVF8_NcuT9L`b@^p=&HK~US9q<{_8P6{2awYK^UW#@7GJW7!5NCM z)g=16*66w+I|Q&XcMsNPH_Ck3zZUIvQ{!T-0ARz|_OIzYMJymtn2HfJKMm_rkmwI|8i2Nwy2>~4 zY1U`hP$Yr&{xXZtYsYkB5!P|9;))CGLdQmg73J0J zsVfr4#FjG}#jn2PhNHbGC&xt!)S4KGnw$$NOM4S%F9@7PRQ|w9!;^gO^}9ZHGV*sH zDlwC$5ak8gf^?2%)t+LW_nzTr6H}TKwQZAi-MqAR@C%vs-O^P86LF(x*1xfE3FtkU zEmZh-!otP#k%_!yhltqM@z^ia=xdgN;t!Y4%r9f;Vq<@dKTTH3!DV^>X5ih}Y7g@) zt*;w)#ugEDx$BDVmF@J4bO|KAu>DC7LoaD^-X(-rBueSZOQ@sr(arYuw`9)@`)v)^ zpXZ66zBzRkt8!qSJR(Yql6^w|>8U|N))6kfltuIK$HdNeBH@CFqmdyQ#lzaB18w;a zIeVmKK@45Y6Qr4(M)g^DD?@A0Z|iS^LRjqxdHhLcaV#@Km48UX9Ecm+>HTd|#gjXO z^sX}bE4fz|t3Y)g{`52+?|26~N}Hc2+XYnw8$Emd;&jfp*2FVsfg$B{U=TAm?>|f2 zM`s;xH+AnxA!?WUY|pB_{)w{b2hL{p;__FD`m}DQTM#KHL*A6YcwG)e2gQ8+hIoX~ z`UAuPPJd?U4=Z{Xbn#Qo4Y4+HnIJY5Bty9CnTZxXpLswDq$aT13mjP{*Jx!=8CVsq z4f@UQPoAiM?__0j7=>B?c6NW(FI?ysrQBoLPyAfj`?XM+5YYefi1o;(qnSrSV3>aV z_e>6-$_}|u<55;W!VFq7Zdg1&l>-yZnn7A`m43Yw$tlWGo+LgmDzj3BDQ8nq%uURU zm3B{|ieLwhG`4%-rqnB#GQ6Ck2so(@8#dc0=&eYy`p9Oj5I!lg@0#xj8U0c-TpFU& z;+D@WaG<$1WzT0@E4b%Uu(@cdwbY`>hn6U4B%sxt3=YxK!F|VDNTGUHi#d3=+OXZx zgv$O#qQpkVW-@~tKVp`m3-YS|th(sUdvD-MNMK+!H=kW}zJPSybB0|@rq|AM6%4wd_wu0pjA9KR-ghZtT(I?F+6Un2rOb!S zh2K5252u`mHBkd1cnG%&RLv?jM`yre$>*RzSJl8h8dfRMC;_6BsPx}cMCH$RSExOX zqQq7@=|CC4qd-q=b}W!F-i8|gA;D@iXb0Q56WIQo_TLB3GLMSLlYi-m_BXskzONxZ znODK_WJ7dz*H}@2?|*>4Dwvze8&2TedAUz%+rv$p3n!+4)q!mQSvd}o@$P8|wq&O- z6P23?<3IAi9D~?Ev_?Nm5J$IGk4^#XqI!tA^c-H2;x%VGHmuyRUF?(#l9NN*}dbA4%i=X66|Rk z4u67PQ~2T+gt&1Y7l!3eZiasfK8Q z=Cuq?@;dXb{$;q7;(0Hsut*RoIgO7)c9d5(GOXzas*v*sD)>VFL zaidFZF^X;8SCQ$$rV5_( z*V_d&b&x}=`>a&)E!Lzp=GL;M^k)z&Op3bjzbUHuMk(WlY#7RvX~|28E0LXzef(@Y z=k()ECg!D&W-(Wc=q6QXGL@()HttW7@72Xh{K1r4|M1XgL?si7W;SyNrGXT=^>qe` zWuQu9cA@E0fb8@UyB-@<+GT~al4#C?2+h>`kqunHdfMsXv+_lRWeN1lP0t17>rKJM z&w~lba0UIf+#|4`%-;i3b|J3bUG1#q6#e`+>gxIhW4{F206%|Kea#(Sf6-xQ$MI#yAXzBR8>}gMzP>?h*#QD2ZkOj=AA=}oO)o; zjmY7OCz2&u+1&rFv0(UvT~}4FXyUegd;K%yyTI4Y9o%uT9Mj8}^}@Aih?D1swYBWs zgMIa!t|#IgAEHlT+@uuQ%MCA*e6$ltn#I6U7ClVc&5XEg-|g~#N&R{8{)_cNWoHJA5TXRA~riVBs2 zh1l5ZxtH0>tNSyD@3{V~nm8wul?wVK5FxH_L$Ph^pLi!Dx)>O_*gu6HV`Z|=ZGAyX z*F}aZXkijkW7C(fXh=8Tz2%>m;+$$Rty-OO!msp__wVp8IV7QH{OUI>bO437W3CEAr#_)#U>IQJI3Sylpb^Ik2EFgU;tPRt@U8a(+p8&W4U%;7_I|LB*X&Gh2meIx=A}@= zO*e0xp!W-nTsK};-aY}fww3%g`wp- z3Y0O(xh-$g%JBnVv$ie zC1iV_#H2e-1%AOky3f_edVVM_`Rs1pkJFeiuR@aDn1sR}(u10OANwV876fgStUm8;0l?I+vcvTqrV>r5xG0z^WYa)8PkTTh-MY^- zN9mH{SiUWSRFvQvst-A%G#`&uCc{wGVLzYj?&ZD_cT=NBzmSwCyHg=M{;on@kPaOB zw6;KZKzSz#UX1~vN5;?AK<4Wk$UAd?w?({8w~aWg6w?60YPX|^dPs@=&w0DQ=Qf9l zGeh&uoSN#evU2F6LE)&uLnep!&2M45lP58>drfV(t@Jea2=}}Psk@uDg0#Db%!p&3 zu_DFA{I!rsh@D6AM!Nz$gi0;rTSoL>8|_?}LAuU$tsH!OI&EYpn*l|4L)TY!6)1iL zYMa_@i7bSiwn2IUDtjKo@^xq*^&P&4qTFnWNrqP1FNdgt$-Qg8VaEL9Q!w}#-PpWy zdfg86$q(^1xx~(?8MMGfaxEa+3bjA7y3ud_)spC1pDKLj9gk3#pD6uR`E;H@%r|q30z|VC z`A&oTA>3vA?$EH737aKLQR?=6Bf6E%15 zMOY9At<0$|p9_X01eA`sW>0ROzM|Q6T;8R&l~6g|1hTM-e%vy>CVN%rIAoM#e52~q zq^v2^A&mlfMQ^4;W4^oK?aT}DM<)=KU2U=2^;irimY!Yrb4laV*=mNB4S6Mpm)99(1X;{| zI}=U*nI@p(INY?Xl|af_8jh%y(`)NyV(q+M#EIGX_x)9|tuZZ4d{)$mQ*yJpUdz+< zFmMr{i-6VNMlfta-R$tSQmq5^HX}2uhP`*%Q%A@7(}-?*N$fv#PBI$VyLA(ZyaguE z>{Gls@MLc7F3lV;W4^Xe8&+zKkuTNqygcP|_}rwXz*p{-3`1pj{_eiJB0M!0rrAGb z&S!I=I-cjvXKSrBx5-{(gQ`7cpDabG{=GJ=fl*FfT&G&iNT!(ZmD1{rCw<~8P1Zi$ zq}EPR_!qCFQq1Y~+@xxyjB?z~ zLaWVOK@nyCL{+BB^txd&JnV4%ruuN?rf-@VeJfom|D|m2l%6T^=BdXeTg062^KQYfMV35yj~1+m96=bcv9obFrap%|)p6QR z-EpjxuxVM$HH+>LU6%3$#kxxV0hmbQW&nE(sX9ajrQJb`FM0qBhT?%S4+E|=BQoDX z2rL^{PX9BSvqxjD=Z}ypx2q^ypC+RAU;z0GY-OHR*9}$vjb;?g)^Xa82J6LC0^nEX zD6VSh8YK)G}o3;-v%KB~YHf^@hgeGLTskqP$i_Z5FFo3_i&xXt-SK^Y=iAH7`9u8C#gT|YnlIgMN7^N1JessU zO0@Mf^-wV88&Z&)dv*EU^Jvon&rskiDr#ytGTd5H%ovmP4wx0PV1>JngA%wMRUr6V z^D^yx9^H5tsr#|M&?$!H%oX2!Gc5R)pywxkcfLSGL$~W`Hy766_>Ad5G^nF~)%$t3 z<8q=0V5xvIBa(AfT>yz~odd#-P0{cHJ^B^GV0iV|OjPoBY--|czs-ezZDq6 zG5jRS4H0dDx^+a&iUUqtZ%_{-F0FT64?+n7<8DE9nWa7LgpgU>_5JFl%mCo15q`>& z$KirS1Yo4+)Ys$4xE=8ek{waP2S{h-vA0|DEOuu)z89l&8{2W z-bEIPC22gsO0TyMOAN>AT2Ew%ZSNT3czqP-#Lq+)D%XHdi##go7C;|GY5Y^HBBC)eg0W4#+9c(6>Jf_eIM>Fsm*(SyetJuJ>gQAa zU}3VT=k@=?*|^)Eo*U-tg5h;vljTV_Hmv%@y=haB*{O3qe0+^Eb0Rkg4+pSEem<&R z`8TUxSu}1|0Z7*fpd37E>MH z)@o30)t^k%jMg^!x(i(_@CR;d7wa&(8oN^0GHy*A+jh>s$TEig`)=`#?vjN`>o*{STFsSsd0+ zmP~~TpX4>A^_#oG)uh2G>SJCC%8IJ$4p>vU^w+UzDa$EduU)GNN%!Nfd9&$^=aBO=^=vXg`{WXDQg zK1Eu_t~qLD!0K;+`YW20Z;xieG(LQ3zY08Mq%_;I7%MdO^tGRdIm60EY`#kT#dRY<3W(L zH2lxon4oB3Ta(xr7aWd>IoQ}`?Xqf&-Qbg_<8!3AJNvSyPD5FzPE)$1+bG-Qa>q@a zL>v(zH0+P?Ar&R9qYSlVnu}CaOwg%x%E$cEK#z|jU!OfOTm6Uge6U#)mqS5oq=PpI z&y0nYU(aR1sIct7n~$I0YP|a#+;SqlW%q^wdR#m#HY_syf`U;JJB>|=SZ|J5Q>*$j zj2a_0CF;rsHM>bkHI{mD6iFhQYNKCY`nnNM@>`bMYMaR<*G|+xHQ>obdm@@{>$_n+7X=!`Mb*-SM=S2Jl7#T?!R~I~ zLfu}f<8DcTQTaw#Fe1l09FMeI`(c%D*LG%^_Y5zoRwOFqjBT;tAUNDUa`(oo6@z?B= z$|;3U){X|mbp$DrxXr3g3&JhtXz!Ot+kD-~cM2bHH?bRhP1~!YM+N}mpgGZrBguf4 zwxLSkv(94^NxTb55a@KqBVp^!lb*-+FFHQ@i~IbHVlbm)107(I(`aLHVUg?$Z8fY? zoUePoCXmD(dDOn@-6wT}NYZ-)n5u!|lEetGnCqXPq>i)c54T%{8JTw>+OM}t+CnZU)1Yo? z_35>%;s?Ma?C%92v#wjxQjs*dsbo`SVI^NbT}iH0EMo{TkU!I!h8z2t{ab7i>gN65b1CeDJLHYJI2O@HzOC;!U(WnOE7)M&V=tBTM{|#5OhJQUh_^y``=e>i zikQv;Y*iznH(^)s?IY#cX;k+8S4ZPO0_!f8;*S#-H* zme2KB-Fa?^Pg#@rJvHiKKl}QUv^5WZ>0XM!`XWZkAa&Z<}%i z<}CT_RXpF#e^T=b-K2Z$h6BEdNv=0nqt~fmHXRYX?Mff!Vgon zkg+6=z3g~4BCz@zTSJ3bN(4SmDbl+rr7nxbRWmxcjw*#2Bua(bT+_ z%628`s<-2CEb82t=HpC=3YEPVXXRc$i4?QJMLM(IWyZKoiNP6cvdq(v2YK*g8r?p8 z_UrTZEx%$wvRoaHyJO@$;{aux8hIR#>QItb#4f$Ez0V(6I`fXpN@O+c_jv4FlgaPe z#1f+xDUZ6tiF=fY({NcTvcjp*xlFIz1IrV0d%F}*Jv87v94vxxgi&pxz#i!rB{vnd z1Pi4EEEkZi;HDbrHalv;wY;`urVv$(hAicII4z}l)VNL3=f~A~j5{yXp$QjSJn|cp zNcK9aEt+~?(2nghl|Qtbu1Y4Vln*Z@D<$?ddh_slY~s52YtfGI9eycrY4h@1Ja!?QPcaSuGAO&{JP8pNBb(6PyO}>%JJG?g$zJz&L*u z-x__;#)r>0KAjGTvC?o%kU<`=C4oZ))GGvl#fenYr! zTwifdQI&IvRZm1+Z>MV$|K}PK{#K;;I+UTlo?TpW_+4wQVM9@oVrs^MjxKmJC#yt1 zZiAR`)$PxftlP#bEzKcKKFQ&WxQ!SsZL4X8V@|!2tX~B&t7G-%hE(jCsj5(vt`I9R zJ%46stT4}9LJiwXmmKVWVKRk#5_U2EZ;}&&{JvtFZG^;8KW5>0`6IdW<0|z1#wPL` zfv*7T&?{n<@~L<~yB($sm#3?`;=axPZ~J{*#l+ufevOfe`L6u*4nB|;y_)rOFOoaV zVvB1Js92uhPCU~RPydy(6Vn@l`(D!PeRL-rpT+f+w= z!{ct>%AV}cAlY8BJD|X1rIl6Tj?h=ZC#5LB8hnS?cG^EE99(bLN;23cn+gl7F}^Pq zK5WKM`AfA-edH@PEI#bz`AD!AJ18O|2t4mveT@g6v_?BS)f8pt>kXo)cX#)693AVx z;HHVG#nOudargy6607}DS*2+xvI)~Eat!U|W)K|O-u<%D++S6@a56OrMm8G;ghMfJ zx9KsHyHF~1pYe|btn)doLCL9S6SmsZtIE4p`sG9MHMr+mGsIJb%o)t3re zBs)Igh+!A5~xuTB;R6rv}R; z6xNW^%ndpBc23^80uj3(9)7%%Vq+O)So~PC|ATy-N&#Ak1|+Oy355Wj^+^fu?+`8J zwKI*qCB%wG)RPWM?tV_ZI9S;0Q!ucU!6HIqcIR?i5fX<0$+t;fIe_P$M}L4SLYb0) zNT{z+2Gebj`*ZO$bGw3dggdfk@R#d#*pg+0pB_TUtIy-R z%S)8Zy`)Sx))LFve-lKrh4^dM>t8k!_UL+e>@5W@Xg04*CHTq1&Z6786V?+h-lT}F z_VAbjAaZ1OzZ?%vcd8hC`ecN}lyaKq5v05W*t|5$wOn&T~qnC(ZKJ;8H&xjH6mx%-Z5*bzTqOKhuci z(Ryxr6zyEb4>cVAcE4JGB6e4tzO#R!QfPCemd}CSGrCptx}ll8JdoonT=Qtmcre)z z@G{h*^e&RSXY@LUsz44JJ+!KqR$DJEiqFQ~*Z-umv>al9CWjWQD7+A=(dWKr)MK{->uO%``u548)NSeIsyG?ewc= zsz!LM(ZCFAWs|32(-#CH2%j5vl)glch=A?beYlLf@r|=s1w8qnHuA7Zz;@Ii*~Rkk zS`1lZlkQy7m5l-*Ywqcgh--EjW#e?>LRG}#!MO``xVy<|_~NFA%9`+!fL5Z z1Oc7XhEaiYsr9CJBg7~XUV94Y$}K-q+QHaJkf?Z;(0%#&l}OA^49XPEn#zL?Z@eyo z!WU}royNn%&RfxoMYGjIVdX%6+~L%5Se2+&O!wdv<)(hF>@<2ez!o~0fTKj6J=9Es zDn=llp`{GfJF+G>e!M!;@m6v?lB96*WuL|5%sS-0EnNI=p9h?Jz60G%Uvi_8`Tnl< zNEtdvw|6{JkiKEAX~!0$di~A3Czg~|yTJE+F1V#AUMESDN&hD~H1{j97IR67GmTMy zk(Jg;%_gfME)=QtxhB#(`SGOE1c~G&iOZa{>nJ4^SzR*U>-*8vZY^S7<{?#U>WIWKP5kAAJ6E?=NN zpwkrkuYRb%WY zVR8N>zEDsd^$wE*kIZuuug_i*bUDq+lI{VfTlHvNm*&ndiaEyS%33>xL=w56jmeBB zC8wT8qF0Xe{UuDbPL}zN?i4i+lfGai<%GycVeNr-jdM*w!{3}j1GZ9>)#1LXi*2Mk z9^T|aTj%Ptq6RO?Qk1>x6tY2|t=863uk0c|Zr4(`v^5?M9b|~+rw|#2CuPtyH)jnrmTt%EUCi53$!{dbKeis)5P7OtWUWn}M z>}cqara7118We>$y&77s@m4) zDX--j=8?mzHObh=E-Q&%g?FYjz+q}}MJN5dZ}f|Io4$O|r#OeqBLj=3)&WkrVxWvx~hvkK34Fe)!h(z$qsO9gJ-K zO`?6sb6>)C9N+c;wr}q`$)50e>Sy3#`8oPxsRnSaI!LHSa+bMWE{`8|+!=bd(gis@ zni2g*N3(;);Y-_W)EjX2q63?e#@+QuN{oqeN0r7HuT87-{K_%>*4Mogoumw@#vW5W z`lEru*f)!OKj3Q_Q=5nTyP;5AyQeS?Dw_`ckpT?Q&=rea65lM(Iu=`Ah9(xf;*s&A zTkK^F>4@kFPAUH~u^j<{WIH)}j4(&$!Q*+Cpycu6s{sq~HD9ugNQTJ-PG~}0oZm4)N6r(-fv)tJ<*Ky1cxztNnTLL zwjStq+XWePb|%<$cbPv~|g!f{LbyIUY2|cfmD8U}QSnY)JJ$M6jX-gkFMEQr@1poLs4*3+9HRfq; zwKW(zE;)sn8(w>-o^B@dqWhAy1W>Fk8`RT#>Nn3*JXYq;x>?HY(N1XePEN$``Y7E{ z=aflTjI+~O6rpZyU8%b&Pf}YkTI__%NsU$)UPsR>kt55ACzgHabI&7Oyh53D&H+5X zjsAPR#^Ieu-cPG_zWXquk{&01+6#o+j5C}~5iE^__*~O@U5_5_`PbSOH=?JnqjQgn zm+nK%^&iZ%&Lm2FBODwDNn<7z3C*Xw| z6g%omi{74&^;kqEY-k^Tc>M;oRIiP;*3WO6DxE6(AM#RGjX9+9et zuphUAEj4_+Ib6)}5J&WSjc`SyXJHuxg(CLQgFVk@Gf}9tc}a*%O}+crypA zO3?^VWn5O$h&HQA!52j+(G++y=a;EF}xM%QW=jUwviFe2)l<+j;)oWJGE~67oq=8M(-_)BV;W zg%}5|-#VQ&$G)zF>v2LOI^m%Qg8kDc&TiTh$aP!)qN1LrPz5usLR46avyrS>W-c*b zXaNF)oC?>MHI*V>)y!%SQ(jh<7R)5WbHfdSh{qzo<$ri1X_O&3je(;l7X+3r0Ip{H z1|yh>2>A9Wc_&ih!S0d`iCjS^eN>$?bfBoMckS-_kfK-Jxb37>o`1P4`hIE|dv>IRQfdHa`WPjl_Nk09DWF3|g-tgCJcdX<^#5uOs;`tKO>B(HJ@y{`=(K zel4t;b7ou#aQAIN+Glvp3ANmCJ3tWugxr^>s?;EeW(Q`Rf zA9*$hoL`4NN%cu{y-ySboR17yLSZAT!B@MxHk1C>a}(oBnNwxv=j=P$9xBCp_{G`T zgJpGv`J@@sW<4#t+xw2t?V36^4ZR+R8s`#C#ha%!h%!yRek*uQ*`(wg9vk&cj$bQ$ z7X>a$yAc0xcD$}Z&Wr7i0-~E`Mo?VibWFjfE1GkEeZH%Qkn#$f7Re`XA%IRy@~=;I z>{;s-viIlrjP0OwUru*cbDuf66y*aGrnAe^Y*=*az{0Ekx^_lAFMsQt-rAfK9%x&i zOez#Ne5h<>;YHon?aT|b%4wJznK=F{E=}*5z4_Dasa9%5M@(S>Gf39R`LUnygC|Sa zV^#m0l}2^Xv%mb$Zfk~yBKT&)?i6LES1*5R(``(}F`F(8-6V#Qb6CMhp zUw{23xJCDdCd$8sgTXSIT@n+lEx-Qh`52&C!9chY+p{#Bw)Z$AQ25e4hT)2cfs1R@ zV9n6G2}>T5pZUJ$+7*(pl7X$EJr$|f=6%N`8Hkr|geG{5SMio$485_|0vuRLfFkJf z>f2XgbG1VCLF625$B=w4bkh>t(v)Ub8H(*PzlD)FetkeI_5xYH>ym79AsZ)w9Fb^o zD*<+>?^|PWIa=?N7%8QN6A*mf4Ml1L(i`*zcqdid>%_F_;lc%gfFcLf=@9OdkM=O!2!b$1Tell5IcI?&Wa3a z9R2uHZWm`DOSzY*{u8)ebczY5`J_}jm5kDR;F{}$FoL}2CtPClmWPWw0_cc%g4*d} zGC6yJl6L#9LT2wt=5gJ17^>psYwKM?6zRf(<|*?OY6v;Gae97Wfr(!qY&H|1xRrvQ zIpTut|N4~b(A{+Z*W-2V;9~Xs6+|5S3XYgf$cQzcg59x1Bgoh31Pjib=XHH!brAvU6yj{ns2lX&WGllR^l#45=&GvI^U0Gsxa2CFTqhNxkMpGqdNCj z)yzgGj;W`XJ5h0ak!`mP^z3f>UB%wn=@Kkn=lx3)`?Vabn@& zt+Go#N1Lxfc#n)A6x7HbcKac+0{il7ugdA6iuv5a6 z(#6O7LudSC%H=@$yMTzV2_zCy`fQ-1{|LPokUzSWVDzs2uMaYUiW|)Iv?3%BkiJEG3R+Jt0i{JG^MdMK{Kg(seFvV|u77(guZxQW{3vl~^ zb3!~YsK(j!&$2Z0Nn+fu`~ifgSzd5lj7iMJ{?p`<3hkHZ?iK1qKWtaRBOzFezexhA z(Qi&L86}<@zpiOZn>4-IaZPyrrm@kRMW_B%b(-nrzi&ROP0(wsJO!Sw=5^#^_7$+K z)6Vs@8MCY}q6@h9$soVedam8L%y97IY&PUU!Ey1VK)0bleij?)O6O>OQcam>_c`pH4}rf%g{d7`|9yu>Yzsd>dczVll&le*}_BApg9=y$;s(nldv zOyWwm=y81UJJrI7E*~A`6`PLQbhfUW7;K!-QEikS+{DW(f0(j%gFZnZC z5|Ho*zUmgWbx4`W&dn`B+uac2dY|Bmg+C_y&oqag-0e9YFLvkAvtI%mnJGCd(}Muv zqdA=Rx9nzgUMHvLuQ@UvBaMCospts$Tm!=F1Y}&agrVZFdS;!cDa^qhDF^o5tO7@z3sQA zC{ojY=<V8BGCiyf8fQ?)u@dGe*!=6#a4i zPy+|u-AA8a^d3ewLtbrT^!o-2PxtF44sx3hK;b)u2L>ym#t&@N#ud~O-nVUn9mc+r zhGHz{Y2Og@A|MEaUjMK{uD%1t|ZPdKb zUI$15eD}#V^YXd2l@php_BWQ}n<(Lk#NA#xVZoBrt?&NteU{%By4-ESdttO=a24vY zXwn=X;l_g~WY< z-n5UhUm64as)!ac$na25oh*^*=-!r*P7RR01N+==ys5EvlP0>B$gV!PkGnp&sx;>n z%M3dJo(t_6dYul3&jHYbfXieUm4H`bg;vOa#>uFl%OSJE=U*_PMb2rnk5g0XSfY_;$U2j_i!$BJ zCjMtTWo*gt>5I}v=p5lf159Q9Mfc_%vSx!FwdfG(Y>n9<+iz8Y>cB=9QJ6azF?7@3 zjmv!TIZG{ME20Hicla4SeOEfiZ*@c15AC5q&11@1o{;1l`SpO|2Y8ApJ&qE)VX?T6 zt-67MC2dYgF_D0tsRLHZI$hjaVvL2=Nj*~$b8<=6_J<8~ZDx{`64mQ3#9N=Wz1<6? zXWu_HClv%0M*Avro^r?iPR)|EN%9xM&W-q_q5epcqyL>A(4k9lh~uUl|CMS-<$I54`-Cf zmu%3bntS*5%l6a>3rDG{mTYc7hhVMoLSxmKblh*^!m6SVHKz8#CfuVD46mBbPoLLy z8=A#6)fH9g$N7q;z+$=HgsLd?F|*z&B!AHSUC>-RBQ$L+CZ1zuU24^>o&2TMlqIES z9vriq^hirf&YHHiB8r(A!2f2T=96OUkEefs#0S4(3oXbHERlcll_*s@`HK+KkHc)- zp-`Nd7_`xic+klSai#NP^DX8igKu81)Ia}FJ{Yt98v8=c2CO-2*)?TE+&2`)#Lzb4 zM(RAoA@s;X2pVaXg!%_AeV zHObE+vSdmARUzyNEIu4CV9i4WASATNAquH{K{Ujv?$^~Tly7V()!s+-gE>WH|2f@r z4Z-2vB-$D~N|xxa7Bt}JC8}n}IFqqTsts`>Q7@)Ck-ggK%&G8;D;wz^$HN-OS&s^! zsHIKO^lDd_(+#RlmBu3%jHu7r&4uW(#<-> zRKQO{MIxBgfVH2?f>-~f@wDD`X^K|>xS~KYhCx5iKJGX4;>@KW>x?Qq`AhkUeO;mT zSa^}hp>y2lM(H54@ze%*;W<3$-0M?2{kp7a7cvTe3ts4^Ru|_|h_r>O@0H?DU`Puj zUPpL*^A}QVjpukZtcDqh8nCah;a7)+y)pUq7kEc^%cHi!30ny3U=tb|7Hsh6s?{V2 zO+qE`8#bLNM5Z3Ev< znG1NY0r4gdPuth({4d)%5Zhmt2zb;G-M;b@A+6XX(E_SKEIidm%^8-#dC0X$iLwwH z_kW4=kB(J8NM{q^Ni~dCJp$W<%z%%(mSpXtLPMF6UJ0nLyJ2`#W}Du;^N$(C&9K(7 zoFTw;!VZy?C7AKsyoL!h)aWKjuOH;?zh%ICRscf(`g|KHOq{yTehzhBGvHQvJ_D__{6Zo6qF!siOmV1Bf>S=q(V#6CV4S*A;ZELsMO%}$F ze4L8xy*{;Z$8UR#J#v0@zD>z{?pv87lX_*7$ySIDUj@bFD7yU%Ide;oZnYHv`QCl8 z7`~*l9kQeitdvK3vsULzJXuS!RqW|N?eoUGO z;=Jw-5dW<$+t1}vXc z8Pa^;$w&p@8GKclTT$cPiHQDX=tcsuSLK)uSE2Qg#OyS_+nQ zf68e4(#fTd`u$G-^Li#XjA2?w-;XWa)S^{j&cYyw5G)&MdEwurPub{xw9Mr)LB6wg;QnJPP9FqqNi#-ojpF9r`XCf(8-;{Pv!%iil}F)jt5jM=nufR zn*;xcsk4lV`j58$3^gLDNJuL%ln6+7iF9`hNOue{G$J5KNq2X5cRO^$(A^*%1NhAU zu6x&d-t%H!uzu%z&ffd8`IfBmMw5i4EEI&L2uce|sg+B6hQ1+JFJ|U^{kNts<74nu znNr*^lN*#YHBG{T=owg9befB0U`k3VZcH|-`S5F7gaL4BW9Yq+OsE*bKO#_&)=AqC z9U5T#XF92`Duw_EMOTzy6)ILvc8dh5$vdy;T0)IMxR)GuD7LR*b)oj29nRCoTWe@a z&DCE6U|7F2)C_arVXv2nOWSyN^XmF;2>VMa7+rKB8sK=-VXlT8m`u6C75=GY$#7U& zpO~Syc*vriBqS7O9VY)_R9CLnvuqm1Tv?&2pS(WAy^KQm zO-emZFYo(EmH1mR$r{`Du@v<;p*sKGFbkBcCpW8ruAEUNxtq_~Dn-TSCUX@6-5eMy z=(<01k(&K>0e@v@PK+M~f00Bl1hyOF2+hqiS1@V*u6J>ADxMx;j$HrUD6W#1C6E4Y zm;+zKutH(=g9ym1*Nu|Nan)|JX#{7HFRSM;)dDh#iR;BV0*k5)O-#E@!DajFnfBZ8 z>)^XRTGaB-b9Ui2JA@2G=I!*%4r0|W-^b;4LG?d|$G2QRJFdTCF~<>w>E^^(7R#EN zjp?xysDLvBx6a+A^|9t9eDLnfN6{k3oz4P-2h1CH$??l-Et)YB%Bb9UCyO&q-5~Y# zCGFK3<=1wH+B2mU{iuhwl&Z|4l~(z1e$AFjzWC|2V(`P$uH4;HTuUom zM13fRH$^KSYbuhiB#;tlTT-jzhJIO4bDxDE;CG6kB@WJ46~$ zKAmGNc`_Qc6>761jW&-X%o>{PvsPBS-}0Elxr_8NtG^H%Tqv?Mm5-Lk&O7Pll8W#u zrC$=4J_quYo;T>tIwHzjHsCf~E--9`GBd_NM(%*j_0`rc!8)5~(viz5>;)hRK%Sc1 zE9r~=`i~HFe^NZ@rbN?I;0ydURQ7e$!NTFkNW?U`#xC zoi^{0D@(ZGh)V0j1~RUS2=)ZE(ojeK2FvkLLbqQvu9AN>QEwdO zoA*s4F(piKx-i-T{j%PM6m0b3i5$a&YJeU^pxe6#m5*Pkjk_w19yf_`TY#qkM@#Cd zgfjG>RzfEs;)HfGt-ta7-$aKDkPmjL$VXTa%r)eu%YaA**>{j@C}ZbR9pBC#vfYzC zW8dZ>gA?e{mrH&OHR=b>e&#{0wfv4E%Hg-fCrAI-Fh@`?&f6u@WxQzhP0OHJQme;L z3&^rmORvoudXWl*FE#Fote>NzcTbb>>uvVA(7kRtiKCWYUZkSHpbuCeai#OF8k_(RN{wVyNHLYzpA=aoA4FZf&+ zPCa(`un>X$(7CCH_Ka@JIP)s&oY0%`+kcL@yXY}q ze@?v?`(3Qm+7eGjPU*;6^JvZs1ZW!O1EJ?CPF=~^gS$dmH3@?n_3N+NjaM?`CNI5xVZ_7oFv znab9?IT%*>t=1a4mmN>GmnQC4M3i1_q?17ggU#TbX8GLZhx0354OZhfEO66UJmKBD zpQ(I4!E(Q3*2DP)8igV`3&xYmuF2*s2P5q~*CnXt!n!qDOa~2Gyv{_dX1g%#7OPYc zZfBEY<$86HEsT=}*G7AC=Sa4jvz3hz$F>9@)s+1cA7XuHLFw#umt9F%q?)mB{ilHikn0AvS)mqFoL;HrsT66_WKE+4K--%SN{ zp;|`%_Kze?_M_v3xx9GFr9atF!yl7`lXC3rD_hA=mm1N(E0uLc1JqOB6z(u25GX^% z)MxwIH3+5DDX~i0nxxGngP0g2Q&G9#Q)woQw zKZs8A;}WrCT7uyRQuR9Otnbnt3O`-a&~kKOzmm`toNFmYOw${49>ocF-;{864jodc zh-nT1g-4`Ob%J0r5sV!93*|gNZ&E{`@8p$q=vhTfUaR`rcgawX!$0A>+MG-FaKDR0 zEBhc8|GC!>8Dk!iU>@fiW~ddEGa)i8`mP+B6QCM|N|!KKrL8mh6Kh8=qv4h`0DA8) z#EhCnZ}Pgn=8X=Y$=vw6IuYl%)bzsbZGEI1YWo3j(Zjtfj(bs%k7g(SR$cbf;Jd=~ zkOVL^>$esOqhrs5pZ!TE2{p%N9h%NjWm}G>*$!8jCSh?=%Lr8TGfj0)+f2Y3Q%`xO zV4bP>AIc4iF0T*^%tCAqi-CV%Cl+T5GcpJd5A;e0cIgfeDOKIILQtVT2I+_P4r)?r zsc>RQk&AI=3(-dnza?%+Lxq;t5h>)lY_98~Ubn_1-xGnXD49ea#LRIT>Mg6gvy808SRy9mUV(-cQwYa>>Z9?7q;_Etmd8u<02O?8+^OA{?Zv?hhn&WBjQNQ zT4yO*mxxu%W?FWSAvf2jK9>8&pfsIlsiS|m4sBxI7TWk>x(@WBHg3jgy5s5 z#v+;Pa}d?c;YsH7G7sxilgnzU6>*zZJppUoxsYW34qZvDyNhwZhlYZnTx>y`*!87A zdg#eizrkV3eA#X)agnKUAknJFFZdA|m)+)@*@*OC`7xB{2>>%IM$zQKsMre^NBZZDTYPOTb5u{oMfcTbHrb!kz3z|Lo=a+K>8iiaO0}2!wQXoJ!V42vJ9PM$XyAfLDMhuFHV8;ihxCs8zrtf8`{L9IN1IOwMack9D9so_QLtHGuM*Tp9HBB^1Tj zpNX;$A2$vq8VCnC`*X}8K=Qzr3Hz!n9p#(jaXx z%9=1@ah!jDls!6RFGld*4y^DM8~>;21u!nV`%5yC`WZSyxPUQ2>qCuu8!KYA=^l43 z&M)|HCeQ;Qb~?z1ZuevE-8nEqTcJipWc}UxZ|=`ncxq;2#bm~D=^h?e=r@yJ;>faB z{C&yQK6Xg(7OWj8U3~F3K(1lYxc+f>T`Uh6Kc!M5XDoAtq<@*hL-;wko1%Eb`3A^L zf3go`xZrI(a`aT=NqrIKAV=_$(~xrnTd583_$W5-yJw&dyn?!nMxn#L7%&i5#RzRB zJYSh6@vA+HBc2M=ql=y}?zk?WKYm>u!b!TEk}EQ8ZvkGAXj9%*@l9}`03K|Pg#djN z7Z2CWb=I>l%MBV0+XGQ``Rde}=dLWbg6rXR_PKLqx+gO_T6pDZ|7w89cf0zMo9+C6 zRfPvX^34v&h1`?}qbR1TO`Tly68Xp26x+z>YsfGH0ENWmB--v7Rnn}l5O=^|a^3`O zr5WBbd7D$bZtA@0JF6lG{?qVjF+Q)WUQZn*?<>5L)B8YJ;*)%H;G9^iZ@H3*%FAh9 zc`~7Lnn9zu_>pEmQ5&3Ps5brb^X%L`V$J(sI_{+<-l5lVe=fg$p`}DigRry!e3j`L zBybl`akR6ipFTNa>NhfmOa^$Fs{h}xA}~XK(3Mm5vs-WN<}z5A>->hDSE`LePgmRY zZ|!u7+XWJ=&Ta^i1IPMgrMY{o(R%!51sNXbbaQA|n=Tli?2{2Ksg2&;$O@~=S8-0W66WLr;vrcSO_`_;M~>lS854A=Y2dzQb|Ef`&zv)Rii zce86uC|?(_C`EMbna0$h{Jpc>MvW4piY%Pp^V4GhQJu@1+^s{XG8^{Njv#6UR&!~K z+@X|(e<1bz7Gv_GDZCPUGX`0ytK3TUlZ;`zvka__;@v~q^n8nSxCJ}(l3ZZ+QQ^EBmzo(ttUvjujO%n(BCFn0lT)Jv7BEfYzJrIPXm%XJ>z0tYft5FtHLn{25t?6U0?cp5YiE7s0fdh z|I$*mA((aADJd#OrU!$(7S*C5JUhVv!U?e+8T-?ULpO*v93A0W; z*7c>MGgEY7Aum%let}n2#${pLo%H_RSQ167zvmsH)MNtIAW+Xx6rE3O2gxrUVY;#3*}F9Sl)IiTWeQ<@cP>n$1y=-rQT-l;y;Y4n)bytmvZu9E4mOJbUIi> z0;96_rXalKj|Oeo=J#lrJW_`y3{Kzu>LjB-LHpST52s`E`+FqCj$dqxg_POJ<~hhV zlQ?pbmenMdXT;O=oa=!tY7B=l&gL41#YjG?C1$KV`95`FQCK9VG%ZWvC8~~nW*oUo zN~-CjN3~OY!W&I8DIw3|w^7}(6f zTV>NxOJ@YC^xK634^Q@0-1RC?5Hm|Fxg8yp*SEJN4p~MkPYH@^Sr08Ovum@3&tv(A z4o0s+pb8%C2Ct2HDo19-@0<=B&6OSIBtaCL4E{yn?%1%dWK6pY^UG#We@y z?bo0Xi`BCetk^29q4se)kIzAMcDYpDdn{GMc`lX9_(r4UB;jNIhhxp9O}E1Qru~8- zYompnU_GM!xuc4CsKt1LJ2ZVjp=@q})XQNJL6M}TXOK%Ja)0L+09^$Jhd?Qdp#HmJ zfgtQORBQ4i?hTTm^({~7jqGHQ>2dR^ScXzmn^Fi=I8Er>TSq!dPzI|=Y?U09Td;}@ zQ}_kQ9w5jI#_=kDRK*w@A8;U^!`UlWryNO#P(92VR+mRsZ1- z_k7klkB&V5vpPt#jOD~AFb z={$#hXZPFU@~z6#mDJk5RF7Jp$KN4$hO&+&6~4XI=xiYo0h>{aU#!=i#%-()sw3K> zfLv8=N~zox(>K`>y0x}Jn&pNC*QtqCf7ZqA^r!PqY+C9}bVBAF7PAPCG_Cq!Vz*jH ztlk?~xXZ?Op5a{Zw0EVwAQMI*cgG=^>#Ads{H1Jah#pv+p{=n4zS z)jBYJn|~JL)AyUd+n#^xm-f$`yo8bl;eK_~*@3Jrhfkr#qJ#<=I}6>a@HM1|UiesW zA%)zlJDE4i-s0x}gtGAX;#k+!<+m+o6?X9EVk3#+RPvEl)0IyrMvdaF+!Zqwqc-w$ zR(lB%@MdVKo9${bMe0q`@%#*9?T3iPn`*8Vg}b!-{cxR@tEpiww_^`Pw6K%}S%THp zZoF=zZ*haYQ7P9EM!ne*sog>!75fRip#Em1R{iL>75UB4xN&NqQFxiuRh2+VHA@+D zejcvuCgOCj_mXOra{1iYt3_FJ1Yj|ilA}{wc$n5~QEcC)fDbk*N?p~cEcyFJvZf?H zR;MEEQI`H~u}VJu!k~w^DC3_+S(&=fgCtk8NEr>y90ko2L8yGe>lIQcZ~IWg7Vkta znO#qkG-@M}#l-D&rYYgOX6K^dY*#*YOpR;IQWU(Y#^){#GrHc+Ar8{!#CCabQZb1Vqk49~H)m5=8N zVk!+UZYz+_*KjK5AF-V5GQCjK6Bq+?)|Y%p&4PuUJMY%jb9Wn42n((x%opX<4U|s~ z=KTo8FueLc866s*&s+9=3We~E8MAI$ZqJlpd|Z&aF467d&)fO$j?E@w0=Tuldes~_ z=-Y&7s7&E#8mg97pC=QB)fT{#zmEld*3;*iq7w?UW(mq0{b%_^X2G&Dd`?-3_O}*# ze9k?v;f9)Uf9PVfB|O;U9~P-6L8eGlf*R{u-6m5l3Wl;7Wt9hxmsQ7+%ZOjp`Ikm)7!!A6Iw zFTOFcM%(Swg&Gcle+207?CvoLe4YQ!tvGQbkG=5iXFZWiTCfGv(XO%Ek-Wp@GQTIE z)hjcL9||9yTvJ60^vKK>gbA{Uo$xEE@gd+QQ6T`8>Ko&ywjSO%a_(9d<}zjI?`tQg zcxxN5&9XKaDt`=KtmU@V6@eraDD~FbrMFWR2sj4FFt9oFU%bP)D%Z4e$@B!lXIGXs z)@AhM3gM)lGlnAj@&>I$%G01H`!j!& zrBByxm8yEvs(aqK#Wu~P2+g8mzh+%TLP`7Zsnyx^S9d>snyU8MiSHUdNpqJm~Xw;CPA>*ra)}yTgwDCC~m>3m~L`e%TK{tD-DyYP`mCw zbJ6v>bU4%4YQyDPZdtgo({+^#OtE*+>>a(fHkv6}6830q*DJJgUQthtR&r#k9E+S> z_Z3Ro6VtW!gfUL5cA?^r_VVB@00;~@UTh?>p{$Im`P_?a8QKw+#_mS%`+w3EH8=+utsi~t76_EW(isq z@|9OM_bnX)0mEv7sjVjI>uA;h;h1pJcS52RSz%ZB16WUeBo}MEb@XyF1@3THMjk!aIY^R~eJsA23GV7AFt#k>TMj)s8>!@H>hM_X$h@08S%5_{S35 z_kQO?>`$k+tb7F+SIB-#V{Y@*6`Oy#i#H=;!{av~BffQcS0i4>g>)*u2iTGIuGj{7 z$R|F}{k)9EoGl#U6E->BajN>yd=2}95M@v#)s%{yzgHyx4-2|?9qFCUk5&}?=Q*wO zD-QWNbQ4Wp-D3e-e%wx^{y$d^H(OMNDhWhc!Z`J#nmSgKtJ^EgDU~nzjxKx8WmPI; z#~+8D5fK!6%*xliTcN)wsGtLfc0RsWPywoyv3(@c^M4a+@^OC%kf0@<>3Vas5Ml2# z&y{8uWvazS8AQmO^_ngsiBi15a&UtCM88vFY5wffVy+$8sbkOmO6%G5YB>V3)`4fm ze9nF1`pIWXo#p7D?g$yz9>!Ry_Da23sa8wnuAHt|(Mt!ft{_e)!sr4Y{`%bV$1W*I z9I>3@+Ua!a1PYgulB(;m=>)YXM;u$!ViW$)6 z59NMK6>9=5V4}gCUU{<cJ@JHP~Wmcs3@R)PbHV1n|9*-&J zl`7}()M&Nf#pAZfcHPy*#mo3qqntL;V&_07;}d?gsD`mCZu&Q%TyPS*+8FN$v!j_* zn4ICYlm!#^cUaJE&$5B3Hwb3f*OAMRBlvT{t>Df^_WHAC$DE>o*MUU z>zlmya#gTN$)$d(%~m*jQfb`}?|gbt{O%C%$*jM5z*`D&zvEJgZWL)K?Z;#+ix9nMR589wi_YK`~A zAC?;BKlhi;S{(2dk_g$%EOjcTv)H6r*~ulw=g(gp@*EhHRM>mnLU1hsc0CVZmXp&N zShpC&ZJpY*e$`Xq*T*K4-vx?gTH{mWN3m;nx#osW?dEOg1}T>Vx0btPB3W;VS8}R} z*Ggc_yQPn#ml}wIC9caDvURRJz|tuHRCMnb%(yQ`Hf z^3rfG1^@oFdQTpO_U^ewDOC^}^0%!96b=wsxcqP~55?a-+P>UIS_`{CC$u*|oG3kRZVdOFlHpag(nM_gS1))&#}j$e53g9V!sAAuIyZ)3PK41gh)Gb;99aqR*D zjsU?ryr=!>V$am0$Rp*EeJ-YJ;+v{j<)wr|pCSKUFjWJT$TpB-t+8z`A z?uji(8ZM?se>c@d%9l-}^^A0M3i3##k8$;LtiAW6Qsj zV^{CGetBj?q{xs}ZQf*TxJ6hKxElgN4O@m6z@I3xn1vlL<{7AryF@sFllwH`N8U<* zPeh-1Ek@V|gk~7~4bcx8MUFF2)J4bL+#2QXle^7sb$0b&@Lc*@ zroD+*3y*%?Z50CJ2c&YfgvZdQbgcb?C>^o8#CZ}!#(9#n#CiXCUy_P&8*TT@C@^#@ zH8=EZ$I!HG@K&;(4U5O6&f;>%MvNJ&aypL+t}nar=WNmcv;6IAI-ki7T@9kDX#!D% z@@JX49f@US29ekP^2RP|(xjOCJ)7O#grg_4NR%t~+n^ggVJ9Yl@m2vq;vs1D?JzWd>8as9>X zY&-;aUr7qLMboqU0d_!};hpjic?9(M|Biq=$9xVmchy_2-B1X;wblsXj$=I@oIjR& z62iSwoPOkHvj=YnyIT&zpWJ*48}L?&DUNP!27`UzjrWT5WQleS$bsWC>bBCJj%YY~ ze7k2kKY?+w(u6E|uAHo3(OZUlknvQ^kF5xB))}WaR5aR1q}H|h6)&BwK|gp#z1?so+ff=}@nk1i={_q|^5LI*(T0NF(x+%Ag%TwWsB7wE z#T-V<4q~WtvlmTaz9Wnr)`HsQ!~CJ~giJhq^81~ z6__g>{_kJc*DyPuA|g9Iw%pM$p=UAK^WV~1_Hmy2Q7(3AX}wgiLPCx06yA^F2G>u4 z_Q;h&ztjPM*WiJP-3&RrV29wmVa8|D@~s-_7W7Yc`5xf%!iJ;pJki)pyqA@xgSs;i zQ}VYO8(!63w>X1tzNJ$Hs%Lf2r(b%Ob_9^?7rVNdJ9=yAcALc5edu2kZFbnZw~09P z>o6`IhXUSK#5TF$(sI$MG5&cgs|c&|DM+_qWSJe%l#L8BV_Y1dhNpLJ&8W{!4r?Vu zfE?`QmZB4lXppb-9)^PMenp$woU&yZs8upd7M312wI;d4#F)2semd0i$W>CDUc{(Y zXtR5)lOjBw(Qd^%_|q$3yScY|qz_Zgb%#(3nXz6ggV^vC+n81ICter%WNDQfv|C%9 z)&4eEDg$oBAB`Sx@B3CI(4sq%@sq>zi@HctGirc)B{&^wTfze zl3U=3MTK^uEiCC{4TkQkD;+)1(i2`&(QDr{PQGK43G%Cx{ z%VeTa86V!D!$O*#K7jd z!Dfle_r?oy-b~Q~dB*j*yA-Lq-_YZ_{4RI3>+UTYYhhU6^08G#BXO>DJIu4cLOX9t z&VF{AN52yN5~JMPz&dlS>;WB#EICopk|;cMFwE<3oGCRn%pFVi$v6Zn&VNp|R4Umr z;1+`r3>+2@cH9!PMfIOdtA&Ue%7(?L#geb1d;*u_`gR&$si~F$ zCw)=9Uxm~)e_8bQ@yK+!(k}a;q3(=_@aHwm~tzG z{fl9^)4(gcQ9d?@JT}DxG7;bA`LibuF~I@k^j=Znty0#@2i z(#;;JX~?sM;HxOpuau^!NrM6zTwnd}`fgVQwnCJAkItl!?Q;$dlvBnMz7M-wHAoEz zAXe1h;rQ9}2y(4E)2P?zW;faM9C1hrFFew1DDu57bX6Poc@SNbx;kw@xXzB+xNc}r zxgM>Q>v!}}uFl_@|0*D7u6dg26AMbrjJgyC?c(m6fzE6N&h;qhhSHT+i6LDT6toqA z0aF|aR8`|EevetM`#P~A@bfbT{XOn=l7LkF)uZ!8TxWOIRo z-{Tn1^IV&pG=p*JsJpGu=w3;{bHM7o;#&`C3wNLYp?ZW>&=VdZltvF9YGPeemkQUgVwpz*$OU1z3Fv2_|~%ZPh`EjRjW@f;PPg{cP~Xq(XD)?9O33IP1Sm2 zO@8(c{)nMmt&T{K_2SkRv^lp#arCPbqoNIh{Jnh!137EGF=-Kz^F-$NFJMF^oO52QHso4q2`Lb((#Ng`L1G{}~v zCoU;!5%1@UXDY97J=)x8PJke5czTv=ieAJnsK$QUE3ZdRfF8?;Fq3*klz=;aF({P# z?KrD4zJG#V&hm)38NbVp;QYrpK33*wt3}}c%N*`(#;Qy&V)7@Pr_46X|Z)r|aFMf4n9v0K@R-Ph5nR zSqHL8wO1doWt3`d7%km*lh+;TjQ(`BeE{FMbzEYyo><>8TQ@~u zrlUrRV%Te@qfCn;5cP1MLS1j~b$uO+hRyJ6F82!86#G#?d$2}{(brFY#ZIxhr1N}IgyjlyvvZt9H^Bi-b-F2b!)YAhW5!AIhMn+$w#bM0!c$!T*NVD~Np#Jy9GpQGK#JsB)%Q+jK z<%Tib2J;LngE0$~)r*SX1FhiQBf;Oy#xw@tqmhV{+$%f46g(|kfrb9GaeG$}j#U0A znt(3g+__f(NQ3j(Ur|&@l)Nj9>vH0>=P-)bUr=!HVhJU@2b)-dzpnL#R4uk0C%G7) z&~X`%mR$y*1z_(0TL5|h)*sm#7{?EPLqv}2X8eBuSmqKCNRsnW-IBj>7lZHgokBrm zo5M2@@7IS`RR6h^k0B)ur+b6^8mqdxqz;FEJLL%x}_xz3;uB9g_B*&`zP{juxOi z$qHchCyx$0!=fgeh~*wcOBV7E6{Zt`4I@I_Hl9$?wuB#o9jS?}RD{v)WZqgyz`u7; z8(ehPB{tlw@#$ME-&b!9{tkiqlGjM>W5K7Q{0162PY0ieJnG1H3eWHdzJt8Gq{iOT z_hsYOVfplCc&aEK%IF{B{&aXK4SW^`8n%jBH*TH!hB}Uu@>o zcMSo^bWGF{65d#5gLGq$l^abjCVGpqc6zJY%$H4t#^N{R@_TUF8y@}qo_{;_OZDtw z{3vEgI4{WPsWuYuH!|ZVYHOlVO-~#CE$z|zvV%;I)iA}RF@?|#eXBk3z5AOuPL`NEZq8$PZAfP1WjGD!cwkL$olTh**Nk+)$D-#y z2o*^;t9E-?1_#mV)?viW%I{oDG2JIT3J7?bwcT;VYJah~^t#y~Gah$9Yng0iY&qhT z>i>M~vKrUCh$O*zXstnOjZ!IwKz(TE*UH5bJ2@V!+d~7~nG@}Lqb1GNoo@(a;k)Sy z1)R?{gd114jSvZznnOVLcD-EZ6TIsErjg!s+h6Hx`3j}Mb&!)Uc56)rq%JrVEZ$G;oH8CCNo z)BhR(XKjwc&ac_L4)qbD>DkIM^)VM%@oL(ohv$1GE#8se4`yE$ykUwaS2HxxZVpYF z+hy=t$Rolur)7vsFZybqbKx?`K+i0e%m@y}gjJoXffA6)hEoz~NKU3JjeGV_DVqby z{u6OhqK~ZLgq*7~Yp+b$&IY*yEtrXhPDjTo!N|Nt4+Q$7&=A^R6|RqLOcod)RpWe9 zhxhPP7KWv6XcHUsC%z;_H8+gEEjgjMszjfTJAk3M$W_-PX!12-P?!cuxR)q|Qro5H z<+sJp0s;lm^`^A8u^7KX7A@@+C;GsPi`;x8;W}^6`^ai)Y76v4tu!lV&{DSx3mHj< zH1nvnHY^)ZjN8z1+Pk)2l%tPCPxSTbhyL;EvO;d33_M41$#!lr3Nx{vD5yUNzQPgu zYN)7~f$Hh;9I<}aEmjsCsI7>!P*r6OMasn|>g7DP6%kOArZ|_?gJyp14(dOJQh_|* zHToKH4t(F<;2pvuWIC z*I&m>BjHuMJA~S;s+H2@hsGvpWIX2)O51j?bqu%XSo;VZ%IYR$jEk?mbc#b2n1-3t z;^Lw-$`%G>e$SShd>>Fqt6-eovpgKpDM@`kL{MK%vPL|8ow#0 z`^e2qwtp@^kxLIYbV0B!pjOPXs$D+rSnF1OVfi&z3Sk#@DAgt9?l(5vVp?KVvyssM z`}v6LkzaSRMz8dyVD`|m%4Ng@X=3r|Y$3y#oo`ZqQed|2)Hg`@qE%}kHC+iQ=GR3E zM~ko-!F|}I{W*V%7XO44sgPTHZnoY^`I9bpm6(Epjq6jyFlWc95Wg3^RYTvoV$5?3 z!HIZu-(PNam^349Q>(SmFR_|to$JH0pIDG{P`OUEpZ`&6Kfjo`mQxU{Q6W!(B|!eS z%xIxVvXMo3a1+d|7fZD4n!B@-bzW~)lFp`LN*^)(BeXt6lV=q?bn^ry9WnLhEpOZY zMwd^U@!k5x-woGu>a*+3-*ZE3kpbpE5H^)`!W|%DVXD4BE>Tc)Zy;?2kjI}K>G130 zMbGp23A(#Lq29>&%{HF;^F1K-Hzd#CrCq@J@PXER-rR&2Q4(0x2MK~RNG0I9L_&^Dcm(7xAJ}3y` z>Lc{J1xL)Hs6>2U_86;T^#urT^(UOTT9DZK3m^BjAC#{(5x*nn(wmuH^|7lBzVT5s zdN?&j7SQ1F7aJWU`aKtO`)%hQE+L}%-9^gKC5$u?39Qz0L1zTQe8ItUx`I=}Wx4c9 z`|-K-u2aeGvV&356l9&1SV->0t=&s>0&W|Fke!Uv%0|8f zC`+ZcAdBAh@5C!1iybu8?0_32z<1Gf@H!_5Sc^;H+BXKoncMQZNls)jmfPx5T87j; zZu0w0U6QNWHWpC5`=0>unU(ZPmDKuSWMzv`BnvL^vrg^bolM@7FWbv{2*}mlyZK1; z2&(#joB4!g1GevxB*s+nVKiYfK@RKHz?YSkz42G?#jqkiec zyV4DCp}A6?ZgYy{?EApmH*imM{2JZLTh#>SjyV=fM~7KX;q5IpM?Ua2lTvfVD6jOL z+^8tCi*Mpv!c)gIjyGk^V@?BCR!NXPp~=yHna?Y}HbG+C9$ zvJ>sa;SWICw%=pIkQR1|+_EcLGqVB)0cH)p<^$O1u;Xj#2263)hKtv=%T5ej`V@CO1jR^-{rrl_u6QrESs&m`d9Bw~L-@dTS?htRwQ`OXE}0 z@>+^1CkKT{IAar)%anFiS2+Q32vl>`dnBtzk>ew4<-(!Hw|gSp4oTQ>_mNRw&xi5l zXpYv1A1}#AOzlL##a)sh61z`Cp~9z;@sFg;@rzQno;f)PsbT%sTAho{xG>2^wjb+@TJk-aJn3)q|>Z}Xw|cH zcPypC=_Z4c2im50Nsx5A;7;{i%7!<=uBsSf?@xz!U??XYB6N;FMIA0^$SlN4V@x^G zyVsrJ`eKi7k93@14;c)mocHIT0T+U2N+J{M!+@iDt=6+Bb^?cr zty6n(K2;`0`mYV`H4vH0LZ{?F%^jhHi@6R@abZk`NYG26xnc805Q~cp?qhBsw#eL20 z*uNkBh?ocA>m*-WLckkJVHfSyqnD#m-^owBBKd?W) z&%CKViZ=qoyfA6H_X- zW*jp)vs*z8u&v8HNIlx_gdnnVBe+3(`5;)qHD4VEBLMPKM#}CK1CZf}sIT1!xeo zbu+VpxLAYDEJHW95irt3w`n!kmyDxF>ZH)Y`=U3GBvfe?Ioy72hpdpgdR(LLXItqB z+2=3~Dymz}YVW*3i!=IqOT6%zN40GEQ5AIITx%1TYBqlvmY!$;pg?js@lkc=aIKQ( zR=FFF_2{_Rk(E1|o#BGa%;t6Ivco?a`r(2cx!R0?_L-l7&_9}>y346gsB=6s{TGEe zWt2_|3F7fuS@9O8trLfDe#x;BQ6_vh4&}ofEPK|x5pB}`ZHc5y(l2=#7l0L#PdKkU z29l&N9?wTMuu-E2bv<2nM^rCGTT>A5nPpSNm}0%FYiWJCo*lBT^fOV&>l2pt!?H6K zC7;d*vIOfYv-pQpt`Ya0-+Hvgqq$`7gWCO!MhY(^y6R`8D$USmfiWi+on>eOmwy7{&g^A4BC~r5Oj3 zP@1Iqo?N3XY@8XNZGbkp;ugHJ(3aQlO~(1gi5*|818FzNf#z(%?V6e6QLaBhT>wQk z+&_Uf{t|dZp@Saio?pjadZ79m&mGRgBy6yeVm;~i-If0$yJ==7zF68c*s=O^UZ|14 z&KJF|Z*Bm`z2t-}!mtqsFywL_E9-Mo$k)73MyAfnE(Xr&HW^l3^Smt}wU9YBx< z2ac94?9V-7vsl|f@%5D^%1Ezm(%wuX^G^1MW1yb@yQx7PbSuDW5slY~8Dj{Kk<-GKsyo7qBMIqnlG2wa&vPut0Me>?s1#C_Bh~U^jBcafq#wiISQj= zg+wj8Bt`;kMEf1FLZz^A3#zOewkf3l!-6V|u<1i1xtt1F=Y) zxEaTEN|IZWqgrb*T6Nohn{K|k<~k}!u2BVaYI8#(K(FP`?oj*(0}rDXJ@6L=(RxM_ z?r26K=P>6UMb_2=u_ckGCO5xLxrasvAI-Ighrz2qtb%zg{~nu8ANvAz>s$*P{2meT zYu2^dAgwl|N^;?BGiHpS+LuF=jFeUXkEgTnYWk1+_5fjogd!oSBB=;SH-boaj~2;+ zbPO0F0@5JTDc$Ah5z^f`ni0}5y7ugMpZk9H2kh+Z?Cksbyx*_ab=~({a4E?lRVlu% z918>2moGSf%>O~uZAWl?y$T#LKB=l$z8Bwgm&^%+uFTH09_`}1VVt0#%pAK3PxD zl@lf7stq1XK|ck@I-dX|$-4nTx0#O7og9jl$y!DqlcdFapvta~z60ZRke}`Fjh)in zy<;U1Mb|BSoHcXUtKG0Z>wTS&+f;-0yC3;x>U2q`wUYzHKopr$VY}?~-s3mOE^}F* zHt_7a1=vm0RnXh(*;dp*QF=;;w=-{nN`3#p$Ke!yL)TFeL-+W7rmq9q8RD$1x&!{K z$$yVObc6yKEq=_3A!Wi8nElH)kWK@?Y%j2Q`#C549w3fxnN-*E8w`i6oD#7@msXVM zQOh3fVF_^bty!7`By}WJ!f-FCd@|bI@O+z?*uINf zat^O_xOD@aYG3_U?EXfrMjz`w9wkNby`>E5sSo2ukycAX- zPza;3`1zjYZ+=*TY0XknVr-6mwvl4yD_a4qJ~nMOajV-R!WswcB&yn)7dDymUw*%k zfdpz>TE$d{p{Omb&BD{l&Ng^PJ_<7b?KlZfi_2FxX_dxO;-#*xGt;DVS7ki52Vvx% z-=+8t;!zr9I zl~+}Z<6uF)8)=kAhJ{o1_S!j{iqN`QAtq~%xBttx&Oh7yum6q4L5I3hxLKsW|K|Db zCAGGOwZk+1`PJy72=0pOFg|iUDm|d zV?DBAlYN~yUoo}giMKBCZyvF};b!Pt*7E zD4G)9!rw4RE7%q$Ur@eP?Uz?{VVN;twiKNJ!Uxa&$89`SxA+pDU22DhgU~4F*XG~n;dBSlnP^n|O06KT8(9-LT^==jr+Oab(t-IN@ zOKH%+qkdsV}w8Rw$>B&{?T!|4T9iY8Jhn zil|3an7H%173H=LPk=R0a2BOzor4IGsoDm;78RV`Lr}g4ofXVMec_H7glHPcOhW01 z{FWWJ#V9qVv!;ag4#y)SJir68dv42ydbT}~H1`t%1td}K{%P&#k?!Qdu$|#tP7iJb?B9jqRMkI^%iAtTrql(kT^6B$ z%Xro{$Cd1pBP~)SHM%fh8GkKR@?sQUs$<2q>FVsEaDCESd@Y5R;KGXmA^>55^pHi% zVM}xbFfc4)$u+2okzNR~LI;$a(s8&07y(a4pqUbqh=3Jb0F@L$z;|g<8gHAGzc~Mc zF(iJktcB$z6mZqer4EeaCC8mJ?+ELmZ6`j!+|^d2_^@mM(jA$;rwW&cITBO2W75~~ zy65MBoH!DxlRZ;()1)Q_cX8Z9d2$xm}bl%y(BS3j;M6`~I2{M$4m8K>q~x49gc2u67;RSh+l7w7fuM809{O<<9oy zE-#Bwp|m<|ToGi)@*;U3plpn`*w4b`Bw*~er^}bfpLb&L+=IL1b0pQ;oQ!P+&jtRr z-$>(@Im3>R&35gnjc5;Wb8Bg5Z~p_s!G{Hx!?ib;u?$eTMgpYBNnaYjk&;sQBHfjo zn(v!;Y7#k!R1V-V2Axmld_+Tz2zu{z-4+Om@jHs}-W{(*iJz5NWdb37qXD>EWI!Fm z3;ZY&SSKEXj_Nuu_dNBGAI{CmF@uK8Aq<+bd!Fw7g8qd#qgi7}#)qaJ4?me|l@(8xdM=5JqMo`3`DvvGEw#OD zTzC=dTlTTlBR6@;+v!So%WXaFnnQ)^nH1LkE%J{$(8^s}ntBP%vH?Vj!?lUDUsYk|mruUpGf&Ly2x9sg@AyT+{k zf0vp5M}{b&XjZkd$#mO4Fi+IirN#pi2mLx#PX|PasNnt>y^N@PZ&M3G5azFcSXH%z zs5Qqt!m(+n2CgzBLb}RlwC)Gt)Qd``Va3_No0?31KqeU zDJbVcz5Eg0qYxPvhg$ zg^0z-0~me^uym*B=LA!Z^tl#PjHmw~JS9w@w{gxJdu_M5F1D|%i^37G?K7uu;oHRd z`rct8(!i*L8b~ln9#20+lv^zD_>{0C86r!c7rwCodErgC+ASSSvb$y$bdJ=QBXMYf z4@uGSF(YLu9J-!u8&jNc^V%w3lp?}dWP>+p48ievA^=fPJUPF^%@^`CA?0W=J$Im) z=HE=$o7e~BUFBc67CDKi+}-_;wxlrDZ3!sLS7rU=t{PS2*V-&}nqMq)Y?F6bOqTNm z$U684iQCi{g+Eo)`V{r0Fy+=#zxz>C)gaGo>0FNgT>*qaG^td5uE@y6O%}2Uku^ym z+?ZyQj0ryBRND(uri~EBdP4->Hh^&3Mt8!$SQa28gmvbNcQDSzy_a~J4(rKZ;$_F5^ z_pecH`V}3riKfo29T#HidPA`%UyR5qw3lFwsUpbAHd9cNo1M8&?pH@UZNrrSN`6>L z?jOCDd#_pt4+e`9#f53UqReikrBn~7%A2W$8Y6Ls!KtNc5Y!l)aRw{Xy?tf2{Iqu1 zup}CHa9Y1jn=|T7`izNdd~iK+QE8=Vi&E2cZJy2&6r*gh*V1w=MSWaAOpsstE%5xy zb1*N(fk=t5q7b3^TIHzbb?|m=g`WSmz_z+YwnI?Kn~I4mVVn}7BUP2wV^x&~uOJo^ zxK2EmK`CmvRg-tbw9=JJzwm^2rlE8=YOUYon>@6;fdUt#con67*}_#`!NJ6!;&<)f=Hfjb5l(yv9cQ(1hrO1pJd!!(62``qb_oknNM z4UPSz#LPG>f%=-BBlDBGFxJf%riiJuIZeDCBIqEa{|}klG17LCU1g)8AmMG37s+Vk z+XIa3yVu6^a4p&UX(*p?A*qdE51EDiM#Fi>T%H)i2G$<6e{1A}Ni+eIg!5HKHncyj z=1LOp$)}8YoUNjuP|pB~o1b;RNe*v&Ca@l3*E}J;Xh?ER{P9DU$$LM}aW_m3t)eDz zL41E4b|gHx5Jrxqe7q6b;2A}5e%V&qhbA7n{cB`FNu%55=)_nM`P_mJKnMCa2 z2aCtOI(ca3v?Jym2;Bqj-d&NpAFc!4H3oH|RhE@3i&vZ!m43RIe}Cuuf2A=y-p$}))af{1vOyww`372OFIac&m(jBIG6OnEU*d3I!m{WQ>gO;^YS_#uOfcl5 z@h6ob>~i71!QkN&y8pw&6Izu|*YcBmOc%Wr!%WN_4Kc3D<-C~1do@J8UrdmfbF63R zh2vc5y-f4IZ>dM+a<*vw(b)2^AmM5N8tkT9fr znb4AY36{leXM8?h+GT$3su+r1nChKQa@jiYs;b-gy>|UtHjhuJErfZk)Z95C>lq`S&yk?n?$YYvhp=%Uy z{=-eDypd=9hB91)lL;pGJa>Djj-a}~%)pfoyfv?CH6k>)VLzPgml&qFhVLs+M-NjEVH~tyxO@W;^8g=I%bh$}T zr{B829<(Z(F_=WePo%rXJl>OpU)Cg=ELMk|dn#s1+hWbmLY@m$E05}Uq^gJ+ICAl> zwx_usK4DYGcU_fEH~b}<9NNX9^sJms*V&<1^c@?!W*>{cRGZZ6GPAi;{B1V6VI85* z$iF=p=01^3ez?AHq3VaUt4gq{nk2XYbIGXvGEKPjIsT%c&Z8VuuPYw3l&a^SM#=AH zcarmtpYxvwcnhQa(3WJWatQjG(cBu%O!E))`|pU(Zs+$p^Tx?ooUPhX)89S8O4D$! zU=WRN2?19v=bNeJMxzW&3ZhxDvh)+RL`0=}^ovXz`PGMW&E?l9&4BkeMfpxn z-9?TvO5H}f4KaP(nWDaBew|t^ZSgwQ1pfGagXCgYs}|YWHitOG*B$lQ@+iBEdU=)l z5j~_seX09jF>t6MY;_ClzMwK|^Vi|%HmwsLXWNn(8M!xkfvwJD|Hb5C(bSrBV|89i ztbyq<_u5~4bIc;Dmtnn{Rb_(d9UvGEU}L*+Iz(ZEsz?}oD$j$TvmG%yZVfbJvjrDO zm=UbvJd!aaA=l@-9eah79>*vZEJl3QEroserV&DYtpfZ`TIG<3^d=c$AmKYWfPvxe_ zeZM2l0Wy%<{0w;VgOo2f$_tHQBa#1561`m^yovUu_Vl~MP!h9yGf%?3V&$@4rr$a% ziTRTv6T!bCPJhPCKFTw?dv}s1pYmL9>IpZIQC=ketSyy47qp{=DMlen+`kINeFR)V zH{p1#jTOvWO>Oj zdxl!hsb86@BwCrz8C+Q^8(cA{{8QPW@TVfZP}sUnC&>sJ{I2Q7#n@#Us4a-HE5xmH zu_?yE_b1*mzQy<55r*2|&+`91QfS!=6)KGNyCDFN9frC;w6(4;a>LKA1o^5jHB^=^ z(jV@-K0x=DEA6ZXS>49z)xg_adCd<8YN<>XcKh!U)r5kgVr8`*b`L}eB zl|xbgg6eY9@%@<0slXurnGtu>iLTa4kzx3#?``kRGAZLYxxcrD&x7$z3=_II$k~(D zx(jmy85Q0XzplZFx8z)@4-qa|L7YI&Y0p9){}}ncE+-xQ z8yZ)pTQc$aKix>dK;w26QljX}M#N{tD5{iZ4?d77cq>*;W0b!HK60x8A8?NuwrSl8 z*iX~T?A3bOLH-lLKELjCi2Uqiu#Ozx2|JeGyNtZryRKl zHU>#yEO`bd$Qk}OZ`j?zeaGX5nwkYA1JxW{w50=tlnE8pF;+xeQN<0fX)f`tHMLVK zI)3u8%I2p~_INuB7<9Q&9yE6uEo>)Ok#g{`=j8p$?s>gAUt6XHUd{Mv?v#|w-9uno zMPlk=7e2u|`71tcEnVV~jPS@~{-@nq76s7#?UEvHx>?G%KZ;&ZYjXFpkOgAnp4v~O zk-O}bk_B7M|!~zLMppfHa%y;GZ+QA0t=y5;f!!{Xb3|* zutV;GRhn_4a33w2ynVzJO_hb$;VPRcp>lZQ!xE+(nGEY?4H5`^(;oIIQK29RG7s4y z*&kniiCFjxmp7u#X^{W@O0<{BUZFa89^$9{cj(7ATY)uYPIX;xd5G{eA+D>#XUq5& z^=cf5*CZ}%lk%BJauWRyj^0Du4oiLid{M`ina~jn$EFNJ15JBro7u&tV0HnLNt^){ z1yAgK*V#$e4Du+cuY8B@LYiO6PZYbuOSQk;8`+R|>KnxIW)LTSr(mz|cUJg_u}XIE zM3|b*+8b?b*GQNasy{@PbM6`< zDsN`IIq5+K-5JEG^+j4JDi6DpZw$4ZyIL4&qpNmxUW;B3{nGByzgem6Y&?-fyKMKy zCMqtS-VRH^Y8|{l1RtWI&Lw(3nll6`&pSR7n>~ zwua!GHgWpR=J>h4qf@`Vlc-%@&P_DLtbWY@c#G7{wUpM{EQ<_7Wg@IvY)eZj=1Ox0 zkF<6uM73SJ{i52u;zuBZG{$c862{Iu0twp6E?})5MLQi`{{ChD`11?Fl|0&I3AKZI zfuik;g{k*PES&HYD9Cs4cDiOY$S&Qpg>w0ZfwSp=W_slz^Xk#9BLMZO;AFOI1v&Xi z?C!vht(F~#DI57^1?KL7J_9g7W;85M|v{ys{IXs zYR8M$NQ#lh_l)OKQl!n4`NaPr5>Y4;$X?~sNr&!^Xu zb+G2yyj-pTLyQSar~fEq*5<5@D?qFx&>U9D2>kA>Op7%u#QM$_y9?9F>fyH-#u5MS zkuQdMrurZvoucolt%h!{BFT59+u})~IO(}VQ^7Zyl81%xsf<%^v;OK(jEiee>bjWA z_NN>KlFzZ<93p(I72}WM!Xy*)%$7+XhKK*4<+zW|4jQ*JU7cdE*6OJYSce5(FmU%V z$`r>KKD9P>i+bm8T0hcMW8&zg6tsL?fSU^KFHiM85i`E(@!V|@gv%wh9B3NfR~Vj! zL{v`x0g@E?L$=Y>Tl7=BH+_goJEKuj)xYp8-@E3LgDb&dzg1joMW3rs)7h@&P=3Ej z#11Hkt+NK0;CGvJ79C}( zF*!53I}kF;QFrxn_>OIAH{0*#JPT|z*;zt=Q>+WUfs~_9kK8*m3*E+}nK0Zxx%_x* zk|9i=R?aZfck}rykOD`t7M1ILvMDJXQ%gatwj)^{p1ojk=dXW*nWIhK99XJ2+$5R^ zJ!hoKT}Wx>;rL{}Toj2}-Gsd#VX;sM0U-GW-vNMLZ925jB3Lb(PI}qBDoH z7qve2Z7M!9j+4t#w3uY~r-KEdycWZmod+nUC7Y+_6Ed?S)9kq*E(5Y<+|e@dIp#mT zllvJL8{&$H6W=CTRL=a(PQJ@m(KKMYKtb^d$vAFVCazt&u6b+2MO*mulqO+5)KMV? zs-M)wU(TKJwsfctoIB-8e4DMz z!z>=K*Z&JkA_eh#@z{$~Fn(K)t=PtE$bZ)rvVOhSlul3I4d`Nl0%ai_ZwZ@E<(Qng z%9Hg!<3$j>CE;+Hw4aEj@zjjVNZu6dE5LyBSi2{_wA2I0xV8W$Y-EC9qODNA3J*9= zzxA-h0v5cQAGzq)14~I2>6X}MRdZuR;cxR6s7;rpOfGdG{Pu4=vIK~^FH5)!tVgaT?LqVU-8qcQ=o2~iQhP?%ZjzTRyWD8*evD zEW1FX@`wj?=mv7VQ#_!i}hxpy`_-ro;mN~zH&myx02{jI#%RUCHlWV>(1E5mk}4E8 zjd=04Md@2I?DlrlE%Zw9bTI+zOS{_IN?o}vEPiFF92 z^+Prd<>L}}zfj)dsI+MhQQNc?PsJw6uWlv|qKKK2R=;2jKUmS&caw0q)w_9si?{I( zE5QUVgXC&5j2~SoM!j3e9^`6O(=)9ZT^4ko*@~x#)+x>VSv%0Pcadhuf7FC)*XGbF z;@GTOj;g>|JC}=Z(pGX4uV=w02S*x{-!6+GE&h0ox=Q+CaZtFOpbD#Rl_opJ^W9kRX&h-4FaYlg zYXZVmmz?yOM3K6RpbyIl+Y2jW>xz_if*7wm^lqJK)zN5^W4{if5U)=|ceKiq%+#qLAM0#*O9^7Q^68bOC5a6)-~{SXUhMpBf8-uouTZsp2>%6cN4bsF8sxMyF%b)UlEe0H3d zdE4#(Z%c>NFg?_L{J|7_bid+$vhBy0S)fWc?b-Hl)MPbXZ*+B4;kb7fC8@n4NcvAI zJt`w^q0;ZXbS<}Su?UHFyOj(RZOVYqwhucpy`($BU4FyV`GD@*VJ!boGx(kZUHGm4 zC5<%QpAZ78h-n=pU!6zJ45`CRVw9)tWJn7F<`-J`buNeg;y2tHMY&XM`G>c1sUF;1 zS7ux;o+e;78-l6j_y!-&Rm)(?IPT<$lc-xca*2_76qdyMbXSS9K$1TNDtb#BCnaTU z)dU{DIXFtRH3UA$R#y|s9drtUa&0tfCyhARIrW^`GuH+Vm>Lo5Av&PM%A9q&goKS! z`0Kn0{f}#lzJwZ|vHga>7a@`D^eN6|Lg`l)xkoBwWGD2Tiv|+V4EIed zGXx1s!KLOp9I|LbA(6j-@jw)7{Ztf&T%5Q>r+XB=F=Zc2=kOvmE$;Kr-5G_U!5Z!! zO^?2w_{})-KMG5wsgQ0NUR zDr)V(rll8@@YxDY$3eyOT24JRAJau9hrIxA5Z?53&Bu(gu-S&iFZul(wfyrf5x3Kz zmBNc2zwK^HTiabdix!2>r>w(KZ$iwMY51orwI_2dS(K)0yoy0oo~8M%O2ZK%)38{m zr&vn}mOCE_CQe)`B05vl2u`8o=bUX`Zuywh<{rOg)M8kxcQE#A@M!Y8p#6Ay#L@IM zRZd*JtX|s*Rts{yS^HT=(a#!8hH$C`mNUb$$Zu!+PwRd-V#;?AIPHRJo)SRcgS+Vv2Ev^*MP2 zZatp`=!ounCh#whVH~${S->9~gSXEdI4Zk)nkiQCs+c%mP`X?$d5ZQ06L4T8tTgMc zjDV0Pz$*gey@F8tWBCvPx-sHa_oJ4}CbuG>Wx+68kXnQU*0H+(1n#lA9~~G#5ol9} z^@HWrxn;~X=jKb!i*`QJtT`=f7*&4~|B1x?j+&^0=u8Jr*Kg-O_W_(UnFUfa{K&fj zz1H>9e0YEu;ul{4)MnyjAt;v+5#cFz|B)6OE|!q) zLM`CE-{cP^1{*9FN$4j3{FU*l$XL9HPwWM|E*ki-v?BBQ+jkk$KL|}giipW0-BXTC{WI=84(EDA>)-!@yq*=3| zvO!9MrHAX6dv{og%{HZ?k{32+Tqser^RxKq=Ek8mo zuXTFR{m~bXQ;5=?EWNN_`$+U|m8$*~5B=<*?uE6{bIi8=c8mjgRm(?c>S$rvj04P? zJ&7k1Q@ZWr$@thfR^qxE%;X|WR~x_mkjHr`nKzIKJkL~H=j*HslH5l7H#lITRA2oa za2l>1UVs1J3C`)|tAM8xsevQ`Vk~{+EUM#+uJ6V|q6}-D_vjH-?u7^Sjig%#3w1Vy z^hb+u;{`$c*&FvXnECLhgOx_pW>|(I}mc$2xnN@YM(AcD$lhDqFzle`W4&s}CZf=?XJw0@O=wsSh zD#lH2UlSMm_2=$u;lC^`7N-<_RsAvn-U-Dua77D;$YUzs6+ge6c1&r(4wi-PV@>yh zl>@ecCp}VI{Ws1Z$*EviwVi)oVU7LEEa9n7ztBti)N{;FNh6zb2=HvptD} zxJ|(7wfmhAOJo>R{JTPxI4WRya>W*Amn&ZK%@;nO$gXJ?Kj;)JEgU?cQYeW%!`P^( zQYE2KCome$!P=q>nSX+NY7ojbdBZh3@mRQ@Xyc8b8FUABT80iXry?0rqKOA%Pa%a2 zixnCNlp{LD_|EjTxQKWcryk`Oys%i@5NGP_krIf0L}=fkSN5$41L3woijbh}bU^&N z-P6utiN8v#@-%s9sc?lZ@IUI%MB7P2QmjtOekFiE%Qmw7qA2E|8M_+zTwn3pK>*rg zD)?uU^qDedh!9z9aN!63dN^}F%Q+^6X5km))SCRfig;i94pb41N2gk*uGj10?(t4X z5WLF2P}{>i;_86W7u42f57(<6(93wJg{JNqPA^Xt9FDv@cXKZ-FPGsQ&KQ}O)k0?X zYZhi~E8BBsZQXczm!-_kARJDb-ul%if<+^Z?Aw>wO`w7U_#+zGE=DtF}qmA~O?k#THst6YZ6a!l4}lPa+)(azO$Wwy&G(q$3{rI3<@R>kW#Js;g!GxJTczZL@7y=p z9F}1QH2zpy5cRb+Y754fcWvbU=pC0E_h^Nch_;^Pqzv(GCKMwihSYjg`1024fjSmT z`{YD{iW*1$@7*&t*);FtpbN?u_}N{e!QxV+m8E4Tct(ge|27;mq0E1Kd#+N%$(yyO zUXD5ExUe-SK`d4eAkE8kZJGl3B!F|`Bhz6;^WlV}ABq-89tLz;r{DZQ8UXzLE)O?( zy%j@rL6U65y?YV;9t(He2?-r(nM!iO@{}jV|Ky`?Dn*OA5eXl%`p*$O;Ed6AJxUUZ zWj#=6t_D7hV~CCQYL^wm@+qVs6+er`ac7wL&4b@Avq0h?-eDs+Fme;<1(Vf^IX^3+ zrSXvxK!k$fsPV1*A%UgVNW){~e^k{6F(d;-C^phKBHJA&(z zre}=K1l#q2w~Zuxxx~~;evc;^7&s=kr9^KCupXYQ5Y2`iEll7@AmUucF^4A0ZPD0M zb=F-)G`Xs=_|!(Smr?HGe&eU>Fr_vvycdio5#eP~is5Hn7Aqbvj{Ir2py*rD#+D!m zQ~fNqk3Hsm=hL2IDmiMw+oAe6ZS7@mG=qo0lE_7kiT8 z&eVwR4<wMvuxTJ6!2ap>T|WzT=TGq-mO6s|0cH7`J>daGLXLEYbM_*2 zm1&`AmDHShUh77Mw+_HB&Q`IVAVU0uP_JGJt-|+Dursl{Z7fzZ`eDKt$;>+Rlw(LH zo~xo;@S2N-APsOq(=>^%llB8$Oyf`XQQFpu?l3F z4)k7w1ni>x{}4P}{C3bDYV#c9oNtSoR3v;V?-gj{ky0kQO;IuF*n5+9xTx@FB%8vc zog?N1h@=tncYExzoTO$ZV}HdiY&*HRcwU-XJgvz9oK0xif6n+R_&8E)$@>R8JAtBN zw34FY&-d^DB+#;{zt-L1>-f(=@?C28Dbbr!O^k9p?k5Lp@-^kN_Znq72GuIBi4=7V z)bj`|nNu~iiko(6;yI>u5^O(P##yO7FFmQH82RFHx1r!aeo@J6v;OkW){xs#BPNtw zieYx4q#_cH^loX~`6_j9*AwiF8zv4;l>f_!aylq2@$;Pk{JwI+3n(aCbq_N3rsrEU zI3qw)@FEQdm5Awu>5{`ktLA!4&79co>sK8MnJmiLOWW}diD@qCF-!~3&O|JGrU$FG z{;agPTq~-a-p+nUTgEk%QqY}5sh)fWQR=uima}ZdxeLmPcn2Quc0}YfIwEpW75A|f z%^qzP4PT@jo4q2Iq2pF9sE!XU=ld$&qxoqVWuL=Qv|?0wrVaU}qAZbO*;@xY{js9p zdLwJgHr?|27E@wI_@@JuqxPT!;~0EzC71H{Q_D`vtc{||Ia*{0M+ERftn9^IWtbYW z_RE*nyqHM1_3L&dqK}(#mXWEj7r6+Qs0J2Qv6}jmuH5bivYEKXSkvQoGy~6 zwMoY64^RpapP9n+l5IZ;r8?WR;3zj_)c_2HSV#j1kH}B4+Rd?vhB{AhR*4*7T>jUC zBhI*1*?{M(&jG-q?b=;{IDl4)D1b2F;y;o;+m8aq5hk*MM`ldKyJ{_L@v{>-hXM2h z5va$9zeyHxzF>~y%sY4c){?H9FE~lhC&$f$<6e+kpH6 z*+}N4@QY}_Y%W{go8-FJ={^L=rckppsx_D}ccgWc>yXp6!)o%yqxNwUST3Wr7;U@o z1&kOP?RB-?Evc5rbDCbqtTv$b9J&(EYRNQ&Be^T%d$`Tep6>_*FxZZ5PenXj1jM>f zP$iX=!SvN69_R~G1Sf_(Ci1*!&|K!r$hVf~bDsOpm6e@9_GN*BE;!$@4!J#XCw>5&|A}>>Dk=#v^wx`g=nqy zJ$57(P z7=~z7nP7 zeA{I^C20bxTGlG#zfxSEy~)ZpvxkRwXr+gkn13k?C$!Vn)Zffw1O2vX(8e`S`z}}V zj416Rhc-2b9$)20+<6Vz8p8BW0w7O<=4e(D&T9`0Icpef(p|#uJMUnbFAw)R79tZYU%3*r{)M_Q{oy zpV;2(?v}-z{`Qu|&M(2%-(A;#Qtmhnbp>AqNV2G_PQLonZoA0L+@+E@?iBfjvXTGf z8$0fRa#fhgw{x9uD!$~OS!4$k*s5FKY6+EV{tY;i z!?0w+rks$-{;8wpGfpk%vc(>cVDjj=oDOG_s|207jfN&=3d_wA@X0ei!IB8RMws-Z z{ZFC%Ce8Sga2>(AkG!my%=<4pl@$F7TV7W1uA9%S@}Fw{gw|7RzKqYKi;p~8z7FuI zz^wliJE*Ia4`N^;swm3K(qf3^B96lXp*sxGYT1ZL(@iPU^+Cppq}3IboBv6rte9QL z-J7cNY5^?>mJ~zFd40-F;o1>Ci!UZ@rsDolgL8E;2PWww;}Q z=@)UvU#?!CkF#pnkgbKrlPZ`(Ts$SyqFhr>7*(>)WYII3IMtXzBDX zZb??X{(1dq{d<9u;!Oc#|9eq)6mYq8q{kb2EIwy) z56QgiXb8F9-EscZ!Q(%=)BgD1>fcU()`!g5__&?ScMMY*@0j+u-!HDnUBj=ACkF=_ z+Ya~SlV`)Rj{%ASFU2n5q}+kBGLN$#wIe+#j)S*oxe3h=#Ik9?@Hom;Ke1kCC(Zo; zq8HuZPt|zzWJFRQZx(^nT|sZx*q&k8HH3P{CWh)^!0Ui#G;YbT_nFtjzyN2ig8F@) zto*n5>Y=btc7Yo2UXZeMbjg-R*WT*alalrNB*31mk4rFo8IR8E)c+!e^`bH66d9Lv zV-`Im>_l2F*3PWTErGGMG@oJvu)MPF_pOaZCl~;VW~?XUZXXR}FMxQbz08RCBkI%h z_F)-e*r8V?Q+lp#|82%Y9#=!C#i2}qu}KhdKzHUvepW*kcMsqQIz?GHosO*rbEDolV`4od9 zFuy^(a{YS6H@YNt$T5!kViPKb*elW-2w})z0F)*hR}Nxk7ydY zJJHi`{YU47y~+KbZ+zA*>9;uuzlVk(8AW#|kgZJKGZhSD8YMkZtmq;OR`gqX{{#*O zVUMwalNz^U;Ru{LUtKv;hB1W-t%LXtzxLA_Fv(R0WC0V6UwS~`IiVKh@df{nDIeEz zTW52Qz=HmJxNq8ChSJc0_E>0adjlK({N{h}?Mx~Y9_T(bu@R%*j4YuTr zN_i704HmtNaZ_p%A@dg4Vp;a77V4K^4+{}Nc7QBC0irOJQ%zu1Gy?{N?YB4d z6(v10`ytlrFTfJIg1eQzEI)64!5-i*S9vMJ?FD=YS7FnRY~ zRaE(B3OV~4k;f>pG1R)biSvn2LZXh%-FG{cbnQLmDzG9J#Dc%EM0&Ec$JYBmNF|q( zW01eG&WM*q2i)@uq>^S-yz{3F>a}du#V_#0%mj|!Z%ng`pPc7)o0-SR6w+O%rx1lV z1roI$WxB2l142V!!~6?Oz;K^>rVkwHQ{Z5$U)mE4o~kmdrCe%NByuz?4w1#!uHd@E zoTadaCo0V*oF-G{A;C*_pvC+;y!alHS^-#bW2*vjgrPEGS{(x-8FyuA!Eg%mRlRAG zN=xUXX>V)IGzuy8X(G~mrsh8H2)Kj)-Z8u}P5N5erc%!@uruMgSh7beXnWntwO3>4 z?LO&#xx=YPvQzE|s(ka#sL<26R?e}-K3I`(yNf>WnfAhMZqL0&c2%~KqyOZ>dGwo= zGTLQm)H39HGtnaml)8tRX8)#K@rX#>UaGk0j(~YRlJo@BgIioV z;Budgd^oNk{3ZPd(+-}%oJ^enZ(ux-IEJ>ic1~plo^8u}fpq(9iclP4zh1}+01WVE z5W|9a>5+Y6fG2TJx*9`G+U^e=Gnf>ITzM*SN2+J&9Z-#<&=D*NK6DXR zFN_)CoqU0P4yR;bX*H5zdP=Miu-yv1rQ65mz?uc<{|XX!e-SD0dr2&I^EUJWnW1tG z37xF#D%@{>zaGbO-@(5tFLVhw1pHuNxN*iJLs|R~x0sFLC*8F%9oP%RsOcB?F1sva z#?)ZUkgKLRD(JBAwH8;0oV4T$WtWWaQe)ETB-d10-N`|~?1P<840?6kQ5Z=5BNXyB z@VE^RrRgvM#aJDEc9>TUd{Jg3KK6CiSonlcnAZ+iO!XgwC`ocScF{kj%S;H zKM()$3@UMhoA%G}VJ%t%CWDMxBx!Y#GOV*7Cjyc*qnPAO$4@Lm-x})R9Zu!IsnlJ#F%qqS&d`Jcj}aokBRT}zuB zLK%0CaAi%659O0xM7SLzlVI43vh|$g1DtT#AeNUDpE|;;O-x?642TKDj(XcT6MSB# zjuw?OI}jJ!3UR?E+{V+1b-cvuOf>C!G+f;9#hQvuls6~+SGLPj>;c6-tyF@&eCE{G zukrX;*biR{ax&*>ivripB_eWhUofOXoPQ*(1$fEj-E8zOa|GRLjJDlrQ5nRs0x$yi)2XOzj@5!fl@Ol>OuL5RLzm4t2b z<^}Id)5fqF&#+{HZ4TD)8!n!_be<=`>j3E5W3id7^q*#ZL?is`Pf7kHn$(@*%#Wn; zkZ`|uFv_e%2QCyPlkBR-Kzcwj4<-Xrjg9{=7ns_^jhVFECsY)bcE+C{I5c%p<}R(Z7R3oh9-;?j(qsTKq>`ac6S6 zaLyO|bwEgnEZ&7h5tL|3 zA;5yo2lmGoqw*lp4X^s|2U_pn%NJ5NfAsil^@X(HlZV9@8_M5**}vOF30C7U#s8sZ zScr}r$4OqUCJoAEqRvd|+1vv;IrQ>bskJfcg<4hrzFyLAu;-%La+GsediDTs3#Rgh;vPd>_;e6ntOP)4CWeC{&xp?&(1zTj_}zTelkL)>_x$5052<7xWZ!H`Ux!Nw zeiJ8N*(&h)-5}Dc;nvVvFu5jvlRgV$rg%y4f$AlGAb!lXp`zDcN9H!5_W{4Om@0d| z?DN8giQPzO#^uuyo8*pL2q_X3gMSxIrt9wM`DRbJLT+|(v8TrNHmf@3B>6tv zVbtP~;DA~WJs#q7!GFOE{rc=eP$CUtfwo|PxifU?Gi36TJ|n*NQo$hT!$P2MX>VT! z@9g*pw@6BI$*KH-?#FSDF%2ORfBp56shqkvEbod7Gdr>#^6clP3a~Pl_b@$K_rlAb zE1K2kf}kVk3ZV~k7fjYw`{Al@8(=s@@BSZKXZaUpA9Z^rhi(|Uq@=sMMYbO+6In0c$(-Z! z3WQIF52=V~23+VJOZXOu!M!LXe3cBhCch+UdxPapcLe8J0#0{Ih%y84IX7qLL+F!( z-_O6$T&AFhNN-8hj2va_svL={?=#WXDESJdSR{vbz~%qdrkr@~-Vk-X1JS!aRvnuM z7*%%qSY+SU0Y% z{KH7jd`z+5pVG3QJ-%f#+V=cB4dk`HtBf<%CXw&UYIfHo937k?Q+KSjjnALn8BgK4 zlF;t6NV(IH|LfswliM!!cXj^y%x>HTJQgIa#5eUD0#x}$4XN)Xvt{EQ_ezsZfdS1EWyls#TG z-u!z%us#PC$T2cK?Ra$9o6GZvtrOErf6bYn>Yeuc;yT-&blmId{AqIB$_VRvc4(-f zvXJl(kr(r5jgA`ERw0(yE}uOwFNND?*<_M|=7yZ_v0BOv|MVxw7u*JBOUC2~!M>dj zU#BwwC1Ct0V((_=1T#&1L?yoX1rsGMmETNDI>yrn$n)}^eM27Oh$g*aYGvMrS?6^i zH&sO(cKN4rb<`&oz-=L?e;6QuS4}Uiq$4dYHNH2WV&u1Z6az+KSNsRf?+oas-bD!h z42#IFf_7E_(-@BS6-$B)zl`+azrn5T*^F1}e}MpIakH+Q)1!QaomAjsO%eWs7l=nnmLp^5h+s8+Ss8n>PrVRdQJpbRpNguv z=n1S4490g5J(UK>buzn9DEgh?{vyUKsP?Xy@rw0tw#t7z>`YAJVXf$J;OxZwUDHD0 zkj9|^I~?W`X~Pg-l}#th8gMn2yk9a((WNR`bzXB-HRyRJ=TZ-E?`HInUNcEAkzR|m zppyS@1b>x{k8(Cjup~k7AUnM&eD zBKW$0Mjs-2$4;|gN$%Rl-p%=_hFgu7?j|m7G<0Fym9 zvn(jY^gBf8o&~HwqbC4QG>_GGM|e$t{Uev^b*nbb0-`>6hB@LxxYW zGO9`A`$E?fQHitvstUqfG3jUMkF7ghzwp2Y_@9L$)6ymb8FN%!x&pCjsq<*quML=x zVk43hhA%KeiD?OzBTr;CED`0m^iRVNF!yEg$htT&QWu(s3q=(8b1^O^J7_!F|@;Ex_ zXKThkVCut$})p{YVyI)msK9|Y4{_TGY1p8JJ+LA6@KFZiX)1#GqV>9i* ze1KE-tOcREp58R1uQsDPnbNm-gK4TMsH9Vw(fu$;KFOL>S35Y%d##GG*%?KJC1_a} zrP8yP(K!AgJf~&I2)D#;%;FJhq7`O&`%n5u46<_Y@4g25jnp2Y5*7C<-Wv7T;l1c( zYK>m2C}A-(D${TSg-YX4~z=uB3ypUQ>hn4|Y zE0=oJu%4PC=4Smx5Y5NShwyx{$hU7osit$oN~gC1dadGu(=IXt2Fl8bcZxdzL`Vi$ zunCRT!j8oO`Nb43YvAtUMuJa7s9C0IRy)4a&}8iLXe4~}JI)V4k737KA@vfM9&WPm4q55ehV%WF6^IE(O8U~r6kr;7xpWKLc^@rf}=7+T1 z=nRJagUSR&Li8$z$EiE<-}RZ-v$qgt(ui{Nc&KgU?Ms>eDcBg&mJbhW=w8^?OlA5H zmz^@m_a83zOUk*nIqB*WydI0ot*}K8Cy1UDtS1Qqw{!8;y>vvbpSt3 z9WXInN6=|%>v}LmKEe0GVd6bIui5M_$W!6}Eu|Y-*>IkQ!3r5cc~&U~=Y5Q=+DFAt znbc`=I8Bwy5$q1t^25LQTTZuBCR#tU3%Hy>&Nr|l{81-Ym*SeL$S0?}h^)Y!`P0=n ztP3uaZ=*DKqmE#$8_uV##8`7{9|41ncD}`-zoNbjcodxfLZJ|wJ9z!PGXiYbCCbqP zXd83S4Wi8fkECGIpMS$~BXh$i!uK*S2f1VjZ;YQ`lR^3HS-0)OE@3Frue=jI(iWk% zQ68SzBmyYSc^l93R7$D878HC{F!VhMMK0n~hk_J@{|uNT1)8&u@I>;BFys5MSRjkkYyt&h zgP!4_^9Pb(P`kvn{S{>wsZ)StDE|-Y-hoAR%lnb;Jo|nDG5E@nkoOgrSwL3AiH+Ec zyRUy$*yrzS)H!cI*SwHa?)!7fm_Lh~(ftj$`@>Zma0>dKQF1X=vDxB#z4uYZaJVyq zUGJN3vt`NfQJh(6)R1F1P(=gn5dclh46X3d~kui1u`IYzixHWw8Z;m#5P=d+r0 z$Go|}o^xTyGE6GjExiQRa+cNf#GVe_@b+hy~M z&TM60eHA;iSr>wQeA*{jA8G+FPs?ly4{?5fuPWv$X=m@y`azigG5SVPq3h;8*N6(5 zK`QPx!yP5SJ&V_$QFlvEo4$1}W0@7bNS#mxkE-H&eES!K@k3ev+vtDA5!gHwvDiC7 z0-+8oZuf;sftBQL+#G%K0e`P20q4w_M#`LJ5sFu(hkOsSIx3xdW*Lcl#=?}83?i~ul2L3xcgw8Ulms9Tvchdfzebh@!CfhCJ$ARwnMfhD13lWUC zX5eqsXKXh9N)ZB_uwB$saux;|+Vne)m@|O{Lf=<{uM4RnfQl`}m9;=d+Z@Ubge+rAp#G7_c#PUBpM>D?ay(aGPJ)=h4G|p6a8~z{NVmWQ!^#3KJ49MNnXAX ziLQ-1b=G99Sp`^2e>!IAP=w7y>UA(*vIjLJoU{SJvhCb_!N4GJz=R-IeBNZ|my?dN z0|FqWM8sNk=l)q%ztp5E zhtlr!V4!as`=k1C@6A8NLCzL{gFxordKDMByRhJGU2nP)UsfJ>eQ=IeXknq)?P^AC z9}-?wZij4VgCPrPI;WQ=?X{8lyC;rzLIxWc7Y|Q(cD0$~atC&hsj*Er3OhUb#9Z5s zswLH1@H&Fey+MuxcUXHjgU9BoIRX8|>tX^CvllZiit66PoL2@LDxM$;&-@l~)_}Kf zUs}?WEm4f?ye||%Y3WdOZsbSUOX+mczi!a=@TiCT9hZ(<0xrf>3w2?GYWY&XC0mZ6 ziPQ6Hv@VDwl_u>W=>dwjO}Qs(tD?07YVBAc9!3>zqoOk6Mv#kOqjGMEEctH^=fS;_ z2u74RF+){3dJi1NtO=2)Gnk&&F@qic0Xk2r@Gi{unYdafT zBwbKOFpPh|HXH41P{(djG2M4P2+m@sXfbHZl_2$f=W|zjNUwCSoD->%idYuaTRLf) z?meVTYe9;6jdYTxx9n4P!jLw`mMxzgEAl80^&>t6?qC-og{|h_u5l+Hm$n>l6m$2oHg-XGu9)e3ivd_(#ie792dFA^d;FWclo%5` zbqEzs@%k?ecR>JP4{)T+N#@T8uxm_T>Qx`h`yG&t7>jKaDqn)yIOOrG)2=iJbXk8sqovmVS<)heCh&_LK(?%v3ltRb2{WL5=y#8p zQ6Szni_*I@RH&BnomYs7RcR-oM~L-O%$1mlnEoPF7eool#?xlkU^?s0CGI?HB--u<0R9wIj1}`a*r@AO*q&19%$u&s#5c z2l%5%yXzv}k>$I-kgTu3Hj#V>95A8HU%%Q_<8GXbycUPx_5i>DQDE^~oK3VE0uH=P zSM`Zr2PEUi&$z{S26!`*?x4BXpRJeq-Xpe*<|kr)>^$!=kh@QAX^0J$Z)QC(%JtNf#|t0Gy~SbD-tgy4No!9g`J5ug7uRB=VAlDNk(|q#&J%R;CRrrh-_e zx9cW@C4x}|yPeNsuKo9x$E`csw|(=c5S5xI1kUG!hug_Rr;0H82(NMIRoS@Z z-RX-A91DlmbGqBIr}|+cXc~HZRrA%fL^3`V(Z^z^6SNuBo#JVRl6^aFPUCrMuGtAa zV*d5WG;{ih(6;`>8+fr7NHstCz!h^WATe&L ze~>s*SX3CtP`Pz5HK7l+6mJG5qUvryZT}o#Df4sET36Z#&cNc=HR` zE`M7SqsfYkbmbPA$z-AyrwbvwkJPY*Ws!&tF@~k6Uzi36KVkhYEfrXu7_gWga!#UMSsWe~e*pbqF5nv9=5Q!ul9 z!5Yl394Lz1o8cYU-J5J>E;iK~Rj2}%CK;`y7z z=vt>zl4UrxtT~)7s*P!KT{!phM^-!Wnv`hZvyGB^CqjmO1>Tiz@2C3SGj4ibVN>CH z<(Nz52RE#byi-~{+}&>6=$G%4f6=WU=l2i(Xk%ev?Jpjk&o4L;aa?R93x8st8aJM} zBxZvFfB-TMB-qs-jMykw7e93Yz0&&>$^Sd%)=wQB>>HO|GBY3YQLMT~O;7=u(#g zyTmlbKpXYKXw_zmyu`&f@h`a(x@VCT9-FvK*HnCE|H@iQ0Hfyt9soOl2jBi?16l(B zAZ(gC=N%F3sV8l4yI%k*zdmTGrYfm%Ut%k{!#~7p!(+r3d6nH&Zw@TN)4X2y7I8=s zo+&+E{`Q@Uid2DA?8x?=3b}(GU5eX0NYNjEe@&uE4iH(h5ZZhPlQK{`k})g5Mc@eu zlz2-=OFKN;_UXP-rB^PvLipLT6F-4R)#%x+rW-~^s>BALQ)%|eRQBS=j_qcOQGX_Qw4eJCwZSs9w8^vE*kZdGBJ#J(cs*_TI%Gmtd6j$3w_@ zS;!N*TF8Dt%fky}G?OU=5-C~)z9W`&RJX59|2jU`&QvYp|HSc+k23mSH zWow5s`96cRl9LDY|=*dZ72mfaPw(%BOeU&w}Lpt)Ay_P?LpyidY~XKgsF zIFb>k9+Ev#Js2%8Cr+?%1%3GMp(cvdI$EUbwmBIc>1xyxPDqxU= zh38LE%&C1eeIa@XxAgN@6^7xEitm7R*jX< z@^wztBk&2}$wba4mzA5)%`>PSh?UjEYZ?cYF?XtHXlNy6(rLC`4t=YbdwwtF&qaQ) zhG~7@@Qq+lrdp|7(ongL)3A3snQ~C$`;Mw&8!NK63!RA>hFGQ<>rl?GU;9|^TT1$v z(DPMLVA!l3RH)y-2Pvsx{r!0yIlcE4%sNy7#%#yD&vJWxl*ywh)zS)#C6uQ7%0XOz zIf`Xs=NuErA2gT$S=bs=uS!f^FYj9rN{15QQd1U;`Hfsp#KAD06@x~JZjevWiU~7C zLPok|A{D`()KrTivPf!!!IsC0Z6Hmzce#1}L=UVbn#4M3xgAj!RoJts{8KLAapnpR zc}p+6xM5ZeU40O`ay*<1>pix~G)RkK{C!oW)>_mLdD=~*aPNSHUx`N;#kb!zv>A7p z*=55Ed4(20mvNs`^keb0#xA2_|HKHkG<$1frd`0=t}IBw$GjeqL3XF@V1K`g+#hG@ z)yD4^bY>b!G~b6vN0X~H5OJt1ELVa*lh}Z21!jD}}Ht618rx1v$gU`%UF5FeOvmXA`oOV$a)3((~o%!m;lgc|JBc^KP#k2E2#h z9L%(Z<6cf%LgC*#S2SggnC&>hf|Av4t&}sWqAIJY@b*jmP_4#NMO!&qD$$hsm*JgG zR%uh&rpA!C?}tm6Ge3XkO0Nwc_F}T7-Iy71u4i9r`H>uuYQb6O9DprTVc*YSQw$^p z6&_O3%^9&jhVWg+$ENpB)Bn!&1vfU|SbhFt?%UZhVYc)5X}?2od9w!*NG2ZBbAbrV zScvSIG#wI_4_TMMygAW#IKsMehDgDYQ0~2Ra~xn^sunFC2v(-r>ECKECO8tVPj#m~ zAp<3^`|G6aGD}Z2>;eaC%)GplA$Qk$7}tRDjg{h_=2cD3KvFg$@MIx0?h$3%CWV%l zmHHpmo%ih&VXffew&=HHB$w~%!u)Pb1{U$LsRBIoi_{v^Nh&=AF^tDZnNL4BnV&q-_u$~UIbR3w_T*? zZ)T!+l34@6iTTo*QBFpDU#-YQlDMmhDb2wttuh(~FD?1fRBuO3EL)PSQd%znAqg@Y zC3)1+2`KNE4&&C5dWm~Uqwv4dhlBHYNRMLOd~slZA8RSZ7)Le*6W5u; zgsYbobTcro zv>LE6u2);!y9(fIUWbuA2!I!I7M!=r@CMmz?}==;=p8E2-vZq=co&T5aUz|#U+cJP6pqaE6& zDfKh4#7&K4Z}iKxX5dCncc^;s0qx2|GUsMcP75`OX~SDlP!1SX;u`oX?azkbxI`p@ zEzSl}M;ys{%CEKiONZ}_IA%d=*kALWUJ^P^;G0vB7h`r^_~KD_`1WFS-BrB$#v+MX zUw6>4@nH5NRh$b_Fr)lKkF2EB?1sLE`?l?C6gB=%$jd6Qo1p>40m9@X9Y`q$c&*v0t@N7_lGhE;8&UAdU?5BBu5)?!qvUkQ!JO0>{ zlMN1exm9k&4nko4d_dgBEey>01hi)`Q z7BXH~WJlzL9d?f8(rT6*hkK)t^7xv*f8r(Qp&n;F|ALq_jAu(x%$9h*LOOE7eG!0E z=I0q_G_;txx^yMNQ>041iF|3z6!F9y;J8Rx1CbDN4#O^NjNcs6HV0ya)_VE%EmXQi zvxDO)JvHVjC)=KcpZDkmRS7EyNf%Ig@ETFSWu(MjNr_B7+7IGJn#Ag-@c7`es3G8D z1O~Uq9Ch$(OZDK_gwN?&)-*YnFsITrdQPEJy$q=#_k8y0{X%RbFozVNLzl^&e>Gr; zN1~$A;hWBm{RfnoM~~rOq^hGQX7Vy(rL170(}>_pc8CW^AtcOisz*=!Mkv>otV3IZ*KnQ))M~rf`eNMsa954j2g}sM z(-|nc#oO2PE16GbL^sVGefzr~{q+V^R1clA3|<2=qkqlLlHUdP zyFTOObPL^}e&-);_3oWw$t|@FgdQgN6jS;pO@zLg%I8YduSt2zGLq0f`ixoBTZ!H;p=@_qVkUv;_{783 z{?T3~CRzD9>Ph#Ptv#h5FGf!`8IIgg_kLVAJO1_<@oshH;~jRY&ObOk=8L`GFnm>A z2$!(`m)D`P%*3XAT%+ZdCRj68*)K>29%eJZT+gn7~d7s*Yk$UUP3_<=7H zr${wQ*b3}dlDegt0ZLlNPL6TNN`tfEy4YuvVri=006>jzqCJdUzEmMbabLkfs8`5n zV=^CPkuZO!3jJdrm5xI3RtX_<8Ol3+4}F z+6`T|AK2rUP%+-bBYs})ej3N~*h2>!6uY>KD2uSKB$#8#1Hy*x8JVq~>P`(@?pL{P0-&v@FKw!x z#^{FGx{W>yal7$S3M%h7L=y?WQ_dqsCcdmZit)BS9_7S(|{`NO?kWA3hx(t{)@ z0~s!V#f)~uA2;+b77ErixoS$8kN?2W5MkDDc;_#W1;d2248la5{1lP1Aeob*7n{zoR|Alh(;?+g01U> zbf?VwAxWK{_bOP2@}8_5M46;EM2(T&XiVk@$O4-VAHSL&gYDR}8@c6WA7+60* z7XOFSdGb0z=|&3v5TI&O49?Ea<-MYA{gLutjL2UZ9^$(Bd`Y*+f(W%(xI<>o07#m6Q&V_L9t*7dxkbN?&(at#kuv|w9`_s28D})&Y_LVa zr5KA(VH2eqi;T9{IWgsj%pfrq)+eNi{?UYqQ?n{jv2?F#xO1=S(nLV?vc6tZn-(3n zBp|KJYglFOH*xmSv!x$r|42o0sN{5w zrd~ji?sqdA(o1xAqDIEAMY_b$+m(D~;YTh8r407`%62`|K%qzgu zMaY(R1Ik~ca=7^K{%2bgQ`sL9N=BT(8&7K#xxC@3-roBUCT;oXKRHVOhFyxWl~?}V z`h_w>_#uFVs31?~uz`!OH*UH z%|mUHuag-R9r?ujROtN~%==>^wa%O;7%`yM0iujN1Gr+0!m)He#~p~qwzPJYltFCR zKgfBtZ!rC31GxBHHB^Twj~8M?=g=^lFf9tJND8WG6Zqj4^{phl_3MiwUrn9B=}wgW zABTZaBGKF;Tu~SQ&=Nj^a$Q=eSM!3eq6fI%-{t*CaJw7B92EZ%G`;UYB~$A3(eObx zWmHl2V1_U4Mc1FpV|lXM?LDW>UZz_rfOZ+(7nu+H)ZasIc5CI zJDB8C_np@xHnT_fR~m^sjhjCRFHOFOye^n4^tsb}WFw=I&SYzvK*jhd9|ePwGyX6ks|Az&VtGW~xTFFbXMdyJf%!eMDZEk* zUngg>ffgiXk?JTv!fakjEKkq$u^Kgyn}LGq&$epcu^S5$Q%Ily)I)s%d`3x2LQBRD zwL9*!uWbyb|G3o>wjN+qdx1lopt3*ULbXXXKLh122H#S2M}%k(>4>S_?eKRU5x!cU zw{ot9S2Rh+v6*N@yN6-r^ka+Q5O7@%J%O5!#|Al;}&bpqj zYbxyfB7z!)-lc4l1tWztZqZLb`97sdzo1+OROJ!D{p6o>}LD;p4X1fV+g+BtIMR3o;m_t5?K&%@4$Z zIBgqZxpd6gIHIDe+*`2TZvM({Z|BuKt%v$OIux!cSsY->x?~QIs*1L3poYKGce!ti z3K&q0PTs<|C7R)YFw7@f^)K188H*;Rk`L6mdf|N7b5V$W#5MgBOvGXC!$8bo%o%>F zlFG2wwYp5y6A)VLfiLwJjv&NvONtB|zqz8A5=Oex@qvxm)s>v{FPGpT)lQx$8-Be3f$;Db~rirM@<9MARy^Bqb4l-_y>8wH-3f%#XH@+|fKgmTvb-`y6=S!deZB8n{`)C}l^cw+b)_9|jjyyk2H zK%|$V**t9Rp}3iF;<@;X?AB`meNS;7%4}XItZQE?C9K}V`W{CTuN{FNA$b9xb4QoU&NEk8?lzm#_(t6a)KTxv22Q6#PfV>O*5Qe?rT19akzgN- zNB4AfeqrytNJdNt3Vp4c2xgEC3P}06yq0Z$rIgv#h3Fm(2p31?nySN~cOn2fQ2+H+ z6l84k=bl`Q%ouY%-aqa+t(F+^#dfP)sQcfaI&ucZnpl;NOXbeKaO+R0gVM2fsH(RR5IF zO#h7jN^hzfT0Fm5grQ$h{0T4alKk6mh9`}rc4N`W^;V+M`KkdsMb-g^oF{fCpq&fW zE9{83YrkO;;WEHwb!*=4{P7hG90=GA6J_@ZrL;tr566PuMOsiq()0q_8iCMKi9j>p zI&;UoucT!HiurvyjY_ycFK!$*Z`_4h*6GUCAK>)oHV=8Qh*g^cw}fm-3G~tgEY41L zYES#-Q%jdRWRv?yex7pq$MyJ)^;2Ee75|znu&D2Pok@NHyU`^# z$GU@)=>SVZW3W|@4OwFh^r<8I%?B{kDcWylB!9vIsCY-tTu6j}APV~_mESgA;7vo0 zuC~)z>mC)qc)I2K!y5d2*!)?mF3%+pNdka&h|NTDg zcZVtQ<8Dsd$ZzEFBJ&!;;~)hIu3pEZf{9yXxsP{MJupBUoUb4L1{gv+hPi;L%;&nI0v-@^9a zK+i-*1-Lm56Zy}t2KcY+bRm(%*Z%&Q-VPDo-7imPx>h_?g5vT&-4@R8(~Hyl!eJbS zpxNJ_Yxm2!XG~UNi)TCSS_;WwdN)=(smrzgt7Il!mWb7hTye<50$b`e9bf4o-cTaH z$BII`@7u$i-7&To2^2#O?}h_jg@#uFe6u{~Uqd#6gy;19hQt+fb$|{PGd$?%2M%q} znHBSGAMY(Retfe#7Y_D%gx@~beB}(%tHxT7MurDc!yiQ_Bw=VH5-RX! z$UU0B^D|E4${mo(mLY=avJ2YOeE0_H^0xi|Wo=IAGW|| z4>gb~rt!_w2A{2gPNwsW;-XxEt;O9{^uS2x>mZc{Sqm zeg9HJsJ61EU`Jj2L)@X;XzHk4Iq>h0jWIX>WEgq1d31n_%RsyH;Q-UwLOdvQEna=y z4;^mOO-|jh^KOh{HC%W2X9Q|bBu@+{hoZALay?I6a@zZ$k6MgcKjf7^d{Fo@5k2!& zKeXfPa$fQD`*=ppnN?>s``7*+IhNB?zFYBwb78Fwp1VyY+(-${6kZkl74KMEwMbTp zH;Rp@H_WJxntBF=6VS#buDyV?IEdf}(lKfiTE>)7Kihu4^KU`qWFy;i0YMF~oNyK#Ct!07YD{OQdAxyhYp zW0~9PP~P!taS?NQzgB>M(W`Z+V5P~B@H106cA z@5#{vVLT@9Y|M4=-43W~}W&CZY9I?oMv0xy%L@CXh-MHTYMood>OgA|g48cXG zlyiYdTs5EdxXwF&ym5x;jN>x4wQ~yqdwoMV2Oj*nR_9r#nC4NqmV{$^nxsdr)Ia6B z0K+>?f%^_W`9!(dE}~_gfX7sFcC`dg;U_@yqyBR#5(QLLE^aXv=-|13AjWQ$RGK6S z%dWLAeqe1z(4{z_#ys6}T<$xsVwJ5@4OqBrCmpyF8JoQN;Wdvs+4=`n6v8y|id#O7 z9&r;K%C7GcI~q4&n;Hvr+q~wE5O-v1$AHConVPTi{(uZ>4p`Als8vH0#fnQfS3|^k zbvbdrRC8tKL+xn^Cwq_lYo@tn_^@*MHuBGxYoudQEC-GVvmF2>({l$7lj9i=ChQ{F zYSEB^#)Mv;{d&^rtvYO5v7k`{4pTMCfy+9~`_>N7*BGxc2S*GUswkMqv~Bw(c~#DE z3zAoa(Q!zG3Ssd4?a4MgX^aW*;5*_%)$K!eipOX_(HD4b7>GSB(DW82pF1E9PDgd3 zgq*Qh(y*fl+x*OSZ}p~zBe}0X?h0OoDKUGjC$4H%f~+g^;qz(^jRIKeVne3yH7)8XZ`a#A*m~@w*;?u6Y12S4@r+DpKA*KT`oZ6~0FF+WB0BT)CQdha>lFd&>4`pf5Pq4} z9?yHa6~t|TIT-jIO1j?gzSe5>N#?npm0YBYo%c&VGCiNOT3lzmNc9Ys)ZQdPYN4ht zp}&4~%T0E6YjWX)_>)mT>~gy8JclUk%serZ1rf43KQN$lUn4zd{R|0-^pXDjL;yk&1g zxZ|Z54()sPFlcozA`5gsSJ~W%w|8|_m~hRr?P_@EXsE!F{FWL1hd+_0rLupjzrt;& zh~B_$lE}cz9_{{t-1TsQY$Y(CG@41!LVumi)2xnSp56KH+^~M`-7nU<(k|k=R^-7k zmamer7^x&f8$#4&_KQlYd5SHVg+(#>DVbr7?=*7*&G0l!J6Px}?G%0Yyo;F~#G?7% zH1h*~GQ0`MCz&%KVdGXq{$g@rcDtId)XKB*r=-^jyOc{Y0Z|Y6YD6hPSxUyU!-ybh zcu3>+L5F!LV4E;_x}OX)sFRHZyIwI)WsRA$3f3M}H4igUh@0F4rMmOuAE8MJ~Pz8e=*5$9p^_kXe2V zoA|*)+vCT|h+~<}9La&^fsB{(tda*=&Q&~IWkQai}e=#v3MK@6ErvZn3*SV9V;p#VUenq&B?CNP7S7 zuIP-I@56cqsCO%7a;|`&f`y+558uY31 zj7y;%$148;z<8fz;l2^`%UzV)n*uTDHI~$bD(=+IwbFn}fY^|JObxMfp^l1@1(Kx% zm7*2|(RDrn52$29AOQbmMJ`@02Fq~3pXU4;2iB;EWp06$3bqTB2N^)3=O@QL1?NH(3@(>V_iYJJTsiOrY1{!ZQ1{uUj+-YD}0mUjv~!l ziIg)JT&tkr$eE=;C3`kuo(QgUH8Drg8BLg=OH@2nYeHhhr5>FIXZe z5QgE(V8=yiM=*QTX!?!?WS~sXd>SbUj*<|Nh=*YAi4Ta4k5+VziCC`MrQ5Rou6r~} zu&*=YPoKWXNJ5cnJ6-(DM)GP6JM{ zeK2h)o)zjO{9b#P+A=ZsVCksEimtE51pNN@zvpUc!fEJ?vBVEGZUM)I+>V3q4}o{X z<^y{YaN)oM74zO8_-aY|Uzd;vyb8#r`oXu zr$MeJ4A7$UF~JCRrK5=l%O&_$7hwF8{xr%x(@D zW;kzl2c6&dJu%w7!++{3B>|Uc{Qde_-5hW+xPupt%5_IX*Ub{AuE>{97t=LEJ@H@g z&p73tl|W>-l-U7#-kdBrq`s7#8%f5J;k{kz8^6XM!)`(?2X66sJ)XB&?$j?Ywpl|8 zEpzH||I4SQlPs<|{?EyuIHOb0(kLek*w`>&$2ZlfEY>s&c|>v+_r-^=cw#t9_@SS5 z9enOM8!$dUg*I;uhzoA)lAmgtt@~12BE0a7^^l;JxXjk?pK$10wl)!$sHLU3nNrDo zH9~gbXutZv)^5$hVN@sgf7m+5?nv8cTc=~&PRF*)O;Rq<7=8l<(wZQ1@d(QhLbEWk$&$7SKxevWd2VW9c; zB5RW<+Oo;tGR?{{uYk*^o$$!J^uhLYcOGEuwXG%NBa+gmE)%W+f)44AiaNUy*E;Z| z6%|r^D$==N3u{UZyfLW4R1@S%7!eT0K|QO9<1u{dX)AOS{hPVpAt9^*#?JA8KFr8a zY)nN;1{@Q}bWS>rYLexKT1$h-K!un51|sdYFrUtZ79i*TYHJ6cw~araT-+g<5SW%e zy4`KSDZP;P!Pf8meKUh7nH$pelsH_e2%12l)m))f!2oRoLyGlWX=x{#EXx=VdITlC zZkpJ6P2@_PlUH{b>u?;mSkY^wPyxQ~LNVwVqchUoyQr5%-LQZ)7z(EMmZ1#rE>1AV z{^$onf(#>@;WGQR)pkmfm0H^V5l)46m(%YImD+K!RdxNpj^rBl?n>Lw=4GpUWDm#r zstq@TVvl^%`;Y@X@z_*|-^Tn_ze_wK2m65r>xiW+0VV|o9^-T;lQM6&=eS77a4OWyyn+FHz^Rw+WmeQYZ z7P6xV`BG6uc$o5Ve4l|U>T81#v?qdfw;TE+Od#2%SISg3^0bHd(CS&-Tu)kU+$WJ` z8RmpJ7|{V@$KWziyuEFD;cMbDUcX#fWg}eD;Hx?-k(H1J&9cZr5XYe9-slgpA%!;I z5Elbk$d$=2W{nj?`H`++1v!L^aD(AZke>xC{kH4wOUPm}I!@2s9(&@3-racPyq8TT zna@Rs2x4l<89O)Qq~`WOKX+S9q}zu!1u?4aQKwd-jpP$Mvtx}=s!#dtq0YIP6Za>| zXOB*odSfnSU=>Xr3QH@}k&4tfPf_;5#5VgO>={YwOLlFF#K< zx9q9!bu-#yEvVTDHQ8j(zsl?$d9%nl?_Bm5-5I^6TbX3%>nELj@A7Smk7=NxDKDRx z-f9lda|T_myrnF0--IqdMENInCF`Z?Xdw+|gg(&?(`lGxU6{ui`vQ;g1fB=0?(B9e zErWi1obn1h&c}M~^9~Q*%va5re*L3uQQT5v9&a*Af#}GrxRHRC)vf!yH5a&rFL+Mt ze7Z=T*&D_QpgmCv!${_t>ASJ*{zxpFgEa5!?J^JGam^+Q@S zfZ1CkaRh-`?oH|QpeFnIOXB;+k1NUDGH&v)*#7P)afv!)VU`e~-P8M%B1JK|BWh0wmBC^EBk)dU5 zQ-QR>WEkE$Q75{gv9kXwRuj-rjm&%MEv@udLQxqa^ehoCDMa?A1rUdi&=$FK~cyx7FornrQOaqXycTB z22)V$8179?6>Q$hhYyj4DrwmFiv?Lm-%)Xnlo#Z-uvM6*G+!iMZ?)y6al)ym4kRUA zz`~(;;R9;)TL^9Idf@fA^dqM>mJh~lnTD2D^qJsSTnIMn*cli(j$cJ)@he2C2YDo)cZ~gHVcxv6B@tEH3C4yb6uNnVO zLCdVdopQZRy|AeimS|(V{^(A(I=c-PVc{$(n~lU;re$0-QO)7p<|H^H%`Hq+PI>V4 z#wQ+WY$o-&I{3SE(kNm&1*4sOSLqTrl`HKQ-%&w=`&5dxq7#a%F{=oGms# zA@6(F+yZCp)wZ?Ub9^B^M^y4Gs-zDz%RHLuIZ&ZF(YVnSKb5EnH}geIa0vbZ>B+;C zW-(-Lz#|UX-NdRM=MzE@NB|sM6(<>y&4E~ zE9o=p!6wq(Hz|iEYZdidf}|Ky*o5~jEp!w z`4NnhICbY{8KLg|owI{}1ViqhR&$S)5@J6X5zV&FJ!Wscs*CaxCR}3@#8&@UQczG- zoUq0Dw(=*g9Sc}^dy#A;kIL(v82ylYh8i)!$245ItT+$$T}FGZ#`s6vfTaEPVR-f< z3M3)WGd)*n)oCKL@myvsyFGZx+4AeIIM)a$HhgYf2bAaLxQsIr{dD@pSoaB(`k_kf zd`fXp@b9$X=Dy%de?V~h@F(udqF!G>j}P>QLEvb%Rz~FGP+T-pZBs#~MPv$>Za!xMNir{9C24#s zPgEWH(DGkwhgc_c%C2XNw7Ej=1P+3p+zz~+{E7yF5Dq-v&~3Rr2q%g=u?LZk0}aKI zDmp4UXMBBE9tf)~DGt3{0x$6owU(lC*S8qaRSQ>e&Rg=l#|> z*(r%`bueq+NL0ZM(?AQqp?|z|UZX`-($h(&$KyQC**P|Vr4Q^|AA(|)jCYj#NbDV2 zCJj22uNwn{N`rLL&L5uSKVBHQ$SRWEB0K^C+7&@OR_0croOHxb6+G<#iRftd0qh*G zDn^xY8!6Fls5zBrn<;J-k#dDJ9D;#l1j8;2hbpXEaqr%e>zGWZR1}fe#Rhr=84s07 zL5VSinql)y4l|cgTKNm!_^V1WtBnSNsRK3bjpb-i+d!(WIEC}&Sp8tm z75(s|s#8#HM;DM^|!s+cS&xH7LS1{FZq z@PK_=znSaUqk0;48f}!m7*JjDI%M6Zrgt#(eF6BGd0)mni`kqSaBmBkeFfE> z#&WM}VvQBI!aa{Q@ocxjql|y287^`^n!QVEw&tHwpowDI4|<$NV^m3~$Awm$qq zZOP3w)Ii$SF^y(C($~MPS2?fkYtVph`-+8-*4yAM9{MT#IC!)YG<1kc*JU_AbvMur zF@UF>ZNN&ey^vDi1yDljnWL<&Kve0=#BQwi~l}V_iM$^P%{ysUxaeJEhuAoZtM<(T{2gNnYVrnfGs&98q zb~AX*hdPy`5B?+{%7N*tLKX5%X!b+*bJSHCtu}kgn-a%15~xZY}s$jZge91 zGoH`-Y`FtBmP4Q7iN@FKswo7fdMhYMpoVq4E^c9NKO_6XM|*vL5Pw}kz%zX?&Lt(1 zDnY>5%ZQWt6{2$B4#ASYb|VZ>KS z|JvG7FNfAT_TGPR&3i|96b`U_N}+#B(Th@!9K8L))LpROXho7rAXHIKJm3AV2ztD# zCSUQr;On*E42hC7cq>Ab=%J5M};wEN&{ z+{RTj34lG&PJAPN5-~hzdfohqw=m0gy%*UVE!Fq#4)s9%H6V7D2obnq-Rkjr8)KJj ze}x_F{l7?DUD8lJf|}ty0ms-!h1H#yv6)P&q2sC4ihCEQ8|j;FZx&DwS3T!F?T?#1 zfS{}X#&BC@L)~DIwHON0w(2}h4H8^1L_qh&0GNGEF}G}KqpXAGq2J#_yvnTOjF+MB zMho2IqUVJ1&h8lZmQYQB(BSl@`8y-x%^EDv3op*9I72JyqAR4Df{>iATfN*W`)E-? zn-k`}CIfJS{JDFD7M`~3&ZOc+;}*2%OiNE)$6v^B4a7<_)IOaYC>2;<-;HvqY8iul z*Z+1bhUpX7N;Bk^O9rp)!sp_0pU!Dv|Cv+wS29aWYlkNE#qVROknrpWz_| zR5JPvIX6256mN&LlA?-nfp~Tz4wT`@tcNRjbs5bnx|xYweSi9H(8|xyoeWrC zd2qYA+wpZKGCE{UL+VM_S1hl2O+&+2j9xDSfjJ8=Qw1mXe2IB!7jjBQnsGTW&06!5 zq?c(59_wK0lWOKZJxsz(cEsFjz*yFniDO?YCWSX!(&4zeZR}C$(tZk74vUaGB1TuO z)b-*wx2w(Ar@uOO7iXib)2J4nB%(^sVC%YF_1l`t_hV5d7q#v|nG zH8`1Q4;(gIJdxEp$|#LNdc&U?6i&qf1X}50<(LR}g1R?NDP%vTr2e{I$gogDqLCa( z>8FuIv;LiTpp}lgjcFg8WPVOu3O#dMV7(ERm4M2(m{Js z7Y=_|`ihWDd#xWpoIWhuVn|b-hH>1GP$Ato?N!qV(EQdD9;;<`-%7^Orby1=hPd&| z)7a;j!iSHV74w%!;Ira`$AvOWUEQZJ?y)8l$U4gX$E2)5EqqMtoJg`OLhQlY|0UKLKs#h@UlE zRy$rTcfU5amgBaMYv6HP4L2g5TF9CWR^q*}5L7hfXO7JQZaCljXb671?0Mb*pL<`S zC&@{(=p{jS*8En~c@`x-cs!Flv~@HttGRm70$W%PoC_=C;_wqlWK8lg_Cbbx+dW

MkeJWqW}yi9~tbfeHs$ zF2XCvVlmKVs)iunw%!slpwqC$DvIk_KU5GY?YK1?`Q$eIk5}Gkw^3W4V&u%Muh7Qo z6(5Pf%H>RBQ|(K_d8vr@OtslEXC2;o;-If~UEIWJE2JX}`c5X~xuWm0KI9S_0QXFMMp8;Y5~1(z>#@ydP5;84AsDzbh+Mu@&Rv z^~Gvcq4U)9;gd%ytyD|ovh&9^I3l$hK(|vAp1ZnNX;h4 z7cyfwxT5<-%Yf{KdvUkl|EAY2=eo-9SZ!{LIe1asFKc%h(|gr+HL8h>2BReV3~O=QKj~{qLy?YD0Ay7}EW; zo=&j>GQu-AW@dM>k8?z{pFuB#`6Y?AwIj)tKrTk z!)pC5sK4G4PB1BZC{c|va&VCd0R%)TtI0IxtaAT&YZmQdLYFSX6xK5}GxTSs&F==y z(#>M!ys?=W&?S0G5Y3O$E0VZK|15}}cO$f9tE?JzK$E7Ih9lt6*VQtW8!6Z-CVgm| z397a+{msP4up+5;7W!MDw?52dKlqf!6~{%!It?!efZ%FE@Q6Ls8W)2L6-ZocBlMLJ zXf8|n;P)QOeeRQ7-+b)9$NyN2IzPUYKN?p&2xV28xRdo;K`{SPO zBszBlHd~@V^I6QU@X_9irf8!0z;w;AZzkj?W4j@97yCQWuS2&2T3k{6{fmK@uqJdI z!O00C4~_)Ff#^1(TKOlPQtLoqgmlA3&oyiAVcKAIh zEwV=Mjb-si_;dy%?$t(E!jnZar=#d|t3{lLe4+0r&-zLnd9yn@LG5bX-JmYi!)o9i zLgOv)nRD{J4Afif7AOac5eG2IkMNLGmI}JD0GL1qLy$rAHQ^sx?f%3Jp+UNX#pU?J zHpsvzz#SqW3P=9JHbOmFh+Bjw0&Nl&f%-wj8H1*5HHR8H>Sxr#iMz)?^avV6foJWI z0j@jlf)c5K1xr8wI%ti_st8~F8|yif&dtv1YBBOfc2OaJJ4E&n&eqfjaXV)Cq1A-9 zP2Ac8+uc7NmS3}0I1%(NZgP!t3 z&dVrur=BtHGlDyuL{bp^h6|T}_;&N3&pe~;i#9SY`#X<04R)$Y474ujlYXi__*4WVI}tV>?1mcquFQm1h90sfwmi0q@daDG$C&V1 zdI^}}FD*>MIwP5s(a1t>L|Lm>@zHP1XLq`(yWHimKgoB;gC;P;c2dBlnh`fK4g)-) zbGiCxrkgeI`;Raw>1f5i#oaa5k80CJkD;2iYlVCOEGYmCV&sHtgnJn8o{ zdMCTM<_YoTMI|=Up^B4=H;hQgY+BLEA%ahPnX6bPHuU4CgT;OzQ;Ad4AqYjT!PQMg zQh2hled@@n>H|2O1o^5^@^J~eT?+KBnk0rRIj@1$fB+RJ?7FPP;Rzg*?T>KPTJJG= z=J1JpO7|o<&wdD_#zjjTVVxUFYBd@85T!eX2}vd8wDd#5pBAV-X+_T4bj_ZLMS-R` zqNz<*Bs<{=b9t+aoH6!-2U&tn)%wk`6h0rF-DY-O1(nH5d6X{JKS#X5QSen2lFl-et*uYRJ&yd)WlDvV%{YQ)k#p>R zs73jqK5Te`luyCYw4q+Qnzwrjy zsckXvfF)qHk)u2j29;UMzQ^;pF^^9j5Q_|$!y27o<76;r1b4$tX zUF`+YjCfU%0b-&$@WgA<#{$ng?=yU6R(K){d%<`OFLThkEf-oYu{DRwUUl1!ci6+u z4l#$@QS%&lx!xkj+XI@#8xCDa*WNR}Hz061{*2H&LjcGT^4tB6=P^T(-74?-FjeWd zb!(VcBnpXUQX(=NP%8KwXyCDCPIp~x1~Mp4cY_S&;{vvz*%Nw=&1kFxeN}1J`0vHx z)}Q>rO#ce**=_6Iux#}0r~Z|@|BZJwO#b0oI{GnII_B?SdYm6WTEBQ4c%2ER^SZIx3OW$l z@_Gp@6Lum9kaqxwhXbxWohOo;?(bco^n4U3jG~_5>SO<3(tgoR54oS|Ki_n{Lj{fX zaIDD#+wbz7GV^jky*6gPJ`-O-co4H5bW6t#l*=yCaesO;oTV&&ZZJo?pMDz?h9UQ! zC>>#Rm=n`WjUl8RpdIwGWFOv>kI^=Y@G7DYQ_}k7Uf`H7Q$o1eq6Hd3axc@ruvJ(JoY^DRS5&68bT7; zjGQ8)i1`$ooz1D#${1!Rb=e#jYiw=hmKAZ99%; zF?wrZ7hT%TT0$O1ym7K{Mj=?a5EQOh5|2}6i%c4;X$r`crfG-dh|Da+Q=ww|EYMg-oXH z%Un(^ugLz!kzwNDfE+^Y&&O>Z2%UP`WKX(M;ozR?5PUDy`y@5Z;OfTjX;aj*RT7{3 zsvJx-A`1S*@bD9dMB^!L;BEIo%~P5Rqo874Y#OG;mM$D76)*&O)Q^4)c-OYfcSK! ziR~je9&_`j@iG$2BwA5%CX6}sAPMM-g-dn8&}1YfGZcLy^q3f7(g|3 zDH-2%Op%GVv=+Msl69LP0!}azv&Thi2q8^y_T!x4MmoBO`3p>u?R5%X^h+Aw`FYF{-Zw#_T z(BKPL&x)a%Lb_riHNrA_P4mPNK%)g3swpAV5rjWm10`6Bf(ghV6W7}QWz;*e3LTvJ zy0<&m4Lx3?J$HMMnFuh(l^>k>H8>J{gMY^VZB+;e&hITdk9sVcm|)4D!7>wUKwiU^ z-2Dy0=&D2#NI;MwMY$P)He7$yaeT&++OCU$yTWs?xsD8mEc$mf(}Kxm!+rR@tS<6p77K@R)z@42t8`YQ|CglrV=1Df@RomfVq`7ZB9MuOPO zKPO$r9oA!wA$|i(ftBm^@Ux`Hfd_4m*2r3z*6e@`2l^}8&U~*Q3-gzMINW{j1wQg+ zKg+19IPYQatg=UG+rqp9wH#Y-kE6^Df4&#!fhrPOxi|htJl&ogYsm)eF=Eh2J!U+G zZqx0MaGIzC%QL?Rrfu5`N0FopYlWm6j+`o9dzZ#m81 zA~@xyXV$G>u*fWT_oqj-__--kg%Y@;axIgSb}GgO(xge>gAm4zd88AYI$)_z$a#Cf zf+q#MROj~)%E)$=Gz_hJmV>|@4b{*EGJdv15cJHu)bO^^>>Ab~wub^%soqiL?_;Cx ze&H*pP?&r(!p)c^uVI`hZws2sOpUQ3M|1gYisvML&eGY0vrl!#F&Jt}8k=I0QZ;@PMuQ@EG=C>5#Z|0{;O{0>a@9iU z*0hdg*2MpgP0484dKt95;#Y5Z5G}XZ^}BCy9W++eidi3lLxz|Gl-22@_LLOGWNr9V z7l7VeVl7zZ`p~DOq%Fz=&2bm_kZR%$HM%k9zkKKT1cIL`t=%TC26z9F1J@c*1livk zz9M{QfB1qEVMsNwHWTP|A)ASv3)x-p1TCG9IA6Bv=yy27pX+&;P90lUZ*&r^IOL7I zJ>l71Y$ParZZw!XVV`$VJFmSt=y&>H{K99JP}v5rOoc9aqu*;j?*FM6xs(i7MGX_3 zfSAQg$wP?~PMKa&W6R?xh#fHzD2JOEL$c#cSL!zd2f&k*82{UHZ))c>jDD=MtB9y4 z?PDiXpHrI07{F69(|Pf&ooF6KAM@0csSUk0wS1YvErRh86IR}h#>zI4ot_j_z*@6z z%SEFrspHY%AVG;(*3Z)+&=V4;L_uBy zc~q)kWmj@?savY8>iqN5Y202#C75u6UlmW20YQ$wzM}>OLhXHSu8*Lo!OZG%J2pSx zA84}^TB|9zq&Wy&YxSfS4dtI(5v+B^|Ii_qc_v`X)l;Y5jN}vKcb9P@%Q%$aq$U9SG8e7AqeI+ouN9#Z0FWI;&r*}eEnfs ztGDCqwQ7bUCYU7rx8Wz5yKs@PVwKbM7~pwLw%ZohwZgnzzin@xHbKHc!jG_!_p^gT zBVERc3LArjS@Q1L-C$8vkv-O-c+oLo9#$Sxq;0%971&rBzf6#+;U;d>HT=3z z<>8tsacu@S@&wZ3ZEMLnn`$VYCGq)-k#%Ir`j&UH3YvP;Hfzuoeg>}DO+UXWZe2Hi z6f=Y!6eoPkMU`HmKhJ)w+Yo^u+0q<&n!lw1?SoBIYfqg&tm^-~ufces6x7^L``vc% z5sjGfb?yKI0A$1kLmXK%9hX%T(|kX@+xyObS1ms1Di$5RdFhKKE_*lsK3LRo_zC&r z-)-XU-30T&X?cOB$)=(AQ95@JF}LpFR^Zp?_&sCrPT#-tK02i~`NaC0eBUb(smSis zI{~50^E>C7UfbFZ$zY*Y`i&@WOC22)29zBcaF1Tcx6l2qiXAoLCSsj{jBMX!#_Ofe zTx(VZgX?PMm;gsFl)47PY@u__=Wh|Wy1zfJ%F0VY-N9STKIi_9)!Cz!Z4&yTqU$k_ zRqq8?p$w@RUxFFltY{P6V^2T+cTt%432aSr`<0a1f}eTI$T!4tEtfZ4uQzkAORVt_ zD1^mbag<&Vwzx=%-_NyPoALCkXF2Bp ztN?_p(wBYb+(45_1z~|(1YNL@7{s3Ex!}#r1nR=E49+@W@T~v zQAX;^nACRYCHq0eZw64mT0e;V1dv80HrNH7-K;B&f;!i|$EIjQhA+hJ;$(Prl@q8B zH-A32A&uj3RL%k$cEpiRJBeQG*O)`0PiCQOZ;223{~t3$!B}RN94p0cPHTF z3+@z)ex-msn29D#I)UP-i<-|t;#X)LgWTp=w!N}a(}UQmg36`vcQkdhJU zz5A}GrBfwV4+;epP- z7|UgJ54IYgX&e6dn8e=><2!kC2Sv@&ve+yxdB&${#yAJDf1L%toFgyl&a z#deO`M`*pyo$N$WUizm_>*6IpFv8|KV~K6xYSY_v6A2vZXu=Iua7%xnOEwv8>|fRo zYnwzX2Bn`9O7fdCU(358=H52kXru4d>zTCjpr%?$HE$(opXxPG@g_EqQmx0edm-#& z$VbUUX)Q;AC=+R()Z-T->Hw4mI1!3p^Cqn31IbCq1@vmX2Tt$)uqBkV*ByohG@mkf zPB7M6!0;)&pan+fo(|ZzyX0T$an;SLN5GK$P`K0AJmkPo`g9xjqtJXT4FL2+4%PVq0#$F3Y*?UI+tweyp*BH}9>>Cg9a(@OH0`TWfq#xtXYUBjq9i z5dAdipcU>Y>ieQl+`j~}2Tv5!dQVsgfAa4bxUe$ay+pusA`!=#pgSMDvvUgmn>GIxW(TR<>)G5t~wI_|VZjx4f>#@+o zvzu9=Cq3Ug9}Cx9dD%KwT^DqXEf?T5re?L-hKR{pKkgN(s-fi0g`q;fwtGY94z+v@ z)StWa{su*s-wNHCWaVWU=H*&Md{h_QjW8epPX-y7({iI9d2SXHA@i1NJV=9oY&BL+ zme^ZXXS?TE-nzffKeFRUF1#?fqr>RqC%pImx1BH7c?oy78|drq7s2YkJ=%kB_JK5K zjk_?n10jmxUn`Pzn`=J5hu_R1A1V+N;VWs9XH`)=kYCGeP$%%u*1cAQG<;%1eqx>IBD!{LjMsilMK<-&p3}ib0T}E#Ju-rHwk@3*2+ZzfD)}dQOT& z1KZaP;5>xHUGew?)IZ43bMS_E>H$U0M<*u{*VotUJ+BR+z)!`8td`omZcU-Sz51K+ zx*1t~HulDuFS$?q;zhcbo(F+Q+CCOJr?%B{+r{rlL)trdcz3ntCA3*mRRZ9GgWY{y z+#40`JQ^LzjE#8z*W8xYu})WgN{bZ3Lv$4uuZl18cBf%P_>#yEwNQ-S4GMGiA_3Wt zbp?AApwE_CY{=fv-l)_U7mF+86Kv1avszpCgsU0>@>|^8%wN=Dp=xwclO!;zk1a^; zr>i=Izl37WEtU3wwW;m5v%H%gXAYa*Z^WP~8m`TNH$;cNQ%Hv&zPQ}^+mW9zRL<8u zmXvwulLcCd`-9&(Wbx!;cl_{oHw?xnO7i4v(l~MQpp{L{80vL;SaS5Eln|p*auIWQ zq2L;XvgCy*N+(F$NJ*9pak%656H)Hwch!m7bf}E-?fO14GzAkU>fSfX^mk#y)hg?Ha9)|EvA@4T33+lCmz<=u@7Fd{!`cg6 zVKu4zvyHYWT+@n$UoT{cghC;~JyK4)n_VoOUvXnou$Ka%|0>VtSlv+lizDYY1!G%# zd)h6AXqN4=Rh6$hkpMs4NrdHQknK*1L}s!|xY-i6dqv`qm5fUqu{V~(oi5Guw3|TS zVy))l#xuH-6GkzYf9UP1RVL3kwCCMkw#p*3x_I-ivI>_ueMWwDuLf{p0=l|)dg8IY zHzX8x^M(nyIgR63u-aSgsC}xJ2hXGj z)Lr!)7n=7E07iPIY3;C7*61Tz4Xa8@0Ah6p7KgkOOse1G%ZYstL?YW${- zyx{W#(_7{;lNoSfknYlc(kc{5KnS6fZh}fal@n>4h`)H?D1l_3U0^M{6H)2}#Yuoy zdHs`<$Zno?!)3NiQtvH#b8WpSms+028lQ9wblvC^Rkb7gXR#{3w4QKSu0i!kaJS8q zP~Ks#BW6fvaW^0Vq=4X{MC@f3GLEuQP#$HC3QoUvBIB=#PIY;elsr z1*+Rl*Im~_N7@IVhBH<`>(8bPa$Wd7gW6VvNjV?mJom3n0)y)6)(8Ev|@yC zZFDrMonYh(hZ13QbG{q1KAL*k=HCw2o8F8|m8u(6 z;NFbta_AzmRJtqgf=AHT$(Bt1J^}WuB;Fd6I&pN0Z&Ip zUOzrQxuimS6EQ7-#Zfbnyr&=&mcbqa`k&qK54jC^vlr%_GQdr}M{s zrvm7+mH)%H^@u}CC7+0kUo};2a9NDAx%B|>324uY^jzXJH=!r5_14-58>hpoSirD} zM;w{B)9?*5VPa&F#r#uIk@n5QT4=l~CK=aJG$bw2Q0k!Apq>J9$tTc_c+Z`ZKI^2! zQ?0hrBHcD4sBxNomAhL?72OEc3Cw|?VzQJwJyxry2rrOAbx3#7lv`%psmv%tp@O9P~ z`SRB~;0>;~ezQBpA30iakgz`TdkOU(ho`5c)llG-hliY@$JTG>H{$K48FLgDF(-0? zugqE`m%GDySTg-Lk7Px(laR4yVn@sumvBlj%jZEzWH!p;dr16%Od>Y3i{|zazM^@U1WN8 zbGsBbno;Cvi{DG(wAXI;AvnXXlk!__R2#k&|CX`tzJR)9gC+v)CApWpVz+)65E#U%!%0M|B;cQ*$J~6`g`x0H&tTfL>f|l8}%hFgjo@ z7q*5T32dhkAC9F6qtvAkVugmo+@=>*>b!Nf$ePmBzT{ffS6tmpk!mwKqljwf!2tj! z;lY2QPo^;E$nMz0gh>3ciw<6*nsL)kBhP*?W@`-1{;o6jWJxY4@#YP;lLP%&qYBSZ zbGt~Q{YzPc&Rv}mzP4Mhnt9pL)s?x^x3#$36GxZ-xv0e+XPw_O`mP)2)4ywu+P|^N zpK$B47?|36dA(f;rt7!@3*9NjGS8o|m(OaRyt3VhM*b-Xw6z|VwqzdZ6a#{^X=5pB z=q^4M&eiDKZI7^42Z`$uMqK;zKUPvO(Ce)x?Ojljmd{15{xJBiH~=btGHmR+KZE1u zn0UX-s}FRyjNy{#Q|Bw(Crm=7cqqM1Ox zEl?D;7zCs8!r!+}l48xD3HQJhg(^njBSuM%xUg*Z z*0W%ui&>JyGKld+KXSnT_Xj+B84JVa&S2k!z;cjcU)MzyA8}&*3I3Tik6HJ$;KI^t zA@2Pj!Mzx0Ye*&r1W+ID0P?lTE1X+1(8q)@=D#B)2$$)fs2IBECv-1YFMiH;oH;X3 znrO{NJmb!9>s3Cy${cs{ru~crdLv>T%=`@^Pt6APk2Nw2%uW8iTvD!*6YBN&w18Xj zdtRw8yFa+RgW5d7j9vzD(xCFTfw-X?t}}w=Pxyzf15$L>d-pRB5mm5a)yr_?%ks0huWHlm#B#4EwVeSP`1uv`{;Lu-Rfj^3ek=PRK6X4VNY~d&}is@_W%DJAzia&q=x^$ zUl>MKA&&<7d+Cum4HKh?+K|A-Mgz%p$B}>gC6K87D1zVlZB-|i#|fSqrC_k8+)?BF zXv^o=V$d17yir^6Q?DSf!Yu|iS?s{AQjg!l_yjxr?FUC{XC zHT>?uBjpX?O*8W=@uw~2q{>?TAL=1f4|1UaK=mRJEzPO;cO&r<*5lYTopOdPRTsa& z((+~aUm{`kZnb^3UL-gb`|2rOTrd)1> z?jm>0KDGT!E9oRT*zdYJjX+M%uJ!<(IB87z=myneacxE_kQbQpSUeWoe_0%3@)oXM z)}MzFnevz?^({U&HYTHSJzXs_EX%E(=*US&PQ{>=P!6AYKx3k=U-=7@YSe<2w}FV< ztXMVzg!_M>wxt42P@oo7B^M7); zqU@eM)@Zl8ao)k(lp^0_O-jq5g)^svVt{EG)oi+`69Kjts1_(YwcS~&oiIuJM2N9rH%#@h+LlbqsxYCo(WNiMID}qd7n){y!BX%HG1Ysu_oNy)%fX3B4E~9 zc~78@k1?QmP~|Do!>+$oSoVm@w8$j!-^B+=@9~ zv*`kZsL`|Eg8$kom}TZDLP2CI=x{53)r!CrfKjTnZrr48!Y+d!eaC?IWK=~-EL4Y4 zIRM6{s+ydh5`3{Je^_!%%E*i0wz;6Z@&XN3RK5%EZ3N_PZzzL%)Y!8=>(vF%+bYi9u%^GdFgZ617Uu;qvXi|O#>FPXr9$;dEVz@wj*g9Vv zn<1wPf}SZx;AT6P;C$b^UKgt%M@$dDhpC+vYVl_%FtvBPsRbkSlI)?)v#83Qz=u!I z$?F6ycheVoqKav>do$f?%phSu&1MmENmft~)d@OHE$?T6pVna)$1FFMckZCD6$}aDNk$E>)pdV=tD>9XMoh3msFlt}q=MGN{ZcHOuP&-KBCK{N99Y=qb2K>wt4S!dksY4F zgpU75)L90#!9`oU1=`{icPI|U-QB&oySq!!7A@}X?(Xg$+@-`8J{W2Zsun zGayzzC8pm5X+cvTY42cZUcWCNpW7f~c#_)=6 z5U!F1uJD&u!s*aD{w_{}`H4@Ed%NoO;hwzKFJ21lhD`%~sU5-Uvl892%re-S_ZP(*Bj-E951CRjGh&Oy@qh&i6OGh3w~e_=;s{z4k76MYV#u(Htd! zgE*d0_eB9itA?85U6uUXe4;0`x{`Yp>~p2my=EeL+a#@cth7D~5>b z*eB@f&k|rw8tMaHUuXVrxr{;{9Bpc*xt6YWAsuTOI4LDL?+29zH|yUB(#Qy5TU89S z-F)&lYA!+}rxjBNS=DSgJq}g^EFzunS3HT-6BR+0d;Nr9}I0r7!Vbv4GpdF-c(qR@X~sdFFxxo6Z8*Pldz#EeLtvo*w7MQf&*W1(Sc+%gvaQ|B^S&C!T zLEoYry_;p3E{wM0n7|+RR#Ab5hj*D-!N?X+6c2+(OH$B&zalh!QPHxuESJ<0Z!6sW zqo%d>WikCP@-Z~lX-*b?Ya2s0U#NGs%Nmz(b_k$xt3gW-{zR(^sEE@`Ga(?mQc=a< zhg`CX921r7kNgF-iXo$u%1G+aar{;3VgfN}ZN2xi$f@fsa-nM62LU z1&oMcCKFf+dMt&B<4QF~FG2~e`V37(H5VTsC5=qVP4jypk=(SfQ0Z+MjK5 zBHZQH<@>Gb-N83gqu#3el-rm$`kV`6Es--O0@@iPvrC`3PE1(hPfWv_hioeLEY8%V2``pngWEZ$*LpEf4~1TIiH^o2+2pz&Iu7>)qxhC@SZO^l)DMgPN63|bzN zbLe*AE?2JoO^T=yvC|?X0$lm|eB{;aZ1#N6^WFb@VT8Sc_^3gfP+r4K{8`B_kj)XS z>469?5{Ozt$ON(E`w`CW)duV>xGewioA{1EH(^fLO` zsWAIs^}VDo^Q$D^(w4%eiO*MYQGOGgm?r`xIclHe5K4^US))h`7!8Rla~PZ9+O~eK zjawd)(yw{X>D^OZL{z}Znkm}gy9u_Hr88{E6>;$m@95b5Q2zntUolU1x8wt~@0886 z?#R6F@7R=nuO-0JubAA3c}zmcgwTV~XBT-^yk(CihL>={UfcX8F);;R0yu3V((AeuWPZerg$PdClj`ThM zIS3){z@cHJQw(4Mr%uz-0l=Zz-{2e0f7?xWKS-_EUPH}DQ(kCwAWmC#$G&r zAcQk`2R#qof_8|jkFcW#MWAVbuD0S$ z&0gb19@Sh>sV8~3Cz@`#99V3^DuN+2ahmW;4=)jo9|}tV?l?=Vx)0G9Le)2#%(>Lm z?}3_aF{jzHtHQ>e-}EJkSfDUlZI8b;)}R=5dgBcwd}HGAl^UBF^h1<86a856b49rj zaam?d*9n~^N|!hU+k-E7Bi{$8m>sVq%xGGwJUFXQQ~RE)A#M;Njby-S%iUHz?Q%h< zHPKNQ+n8brww4hBKZJ}{L`TbuU1XN;vnabhl@n7Akk@Rq4W>5IFus1ZaeOkPx2CVF zTO~~00N}htXZKx@asF((zJD;bhExGf5%q6@KL?qcqo!v{^o(u|A|ooEtEqeC)j>SJ z`~geb14jgc;TOjyM_K$KGuY(YZ21~f3*!L1TXuHe+{CjJHuihKp z7)SF=Q@hfE(+S9egaew;S317qsEEs2rhucSfA)niM{aAhmxloTCQPd;Yc|>rhc#=6%4$Gg~c{>&!85b5qKoBP*n?v%IIh%u4OkDPNuVy!s zQWqSuJeo)(+0BfVu+=iX71jpq^-v2Y5O2WoA7(i)ieYUFLSP;P0k0z(He)+tlv%{D zRNdg>ouSrJuP<21lcG+}L^lcb`|C*|K%t-Y^Yt_H|7t4ry+ev;7<@Z(bD`KX{TTO2 zO}Aa&Zt__$_LFlfbK%)B_e&Wng!RPH#}Q=B&S*^LLVLpf{lR{(TYcXcAcwIr#Fp|0 zq)P%M>xHmeZ`2_f7kUgNGX`=PUI~)SS&?2ycCgbP#(M*O%d&T<>#MRhTjGpRzo)Iw zCHOL@JH`pjTOQM7wzjcJP8f5nd(_1ND%d@GN#)3y=u!wA8TL708fFccfS^U)|FbI{ zLu&S5f_Mn^zVUnjp>GGf7_k2{_We1p`kakrvVPlsL4`LA0qeSE+-N?ewHZg&40zg} zQSmM98-kvy_8&u3esM1*f-J1EBoH{X8=4v$sY@{b^HF0gkV*c4nOCugJApm7EE-|r z>E4n!xXRdkm8j~FtZDggMpnbq<&D8|&6Ig5AbykjEW~e@l5wr+(D=BEp=ZB`z2+73 zD`uOA(Q6*d7l@ztgYzJG`aQ+}3H#0#O4=7Pc0ZuqpmGR2AE7wj7tcTTk>y_sfZ6#x zKTLT2E4JA8oE@?!^BN`t3PqZNW{wb^Ml4q$4kOo zmgfWo@G5}9VnA=q8!pfK8?7H~_PkEK_T28Y_B^gwm)sA28{W@dt*0U0P7ofNWHul(mZv=O z-gA819++f^5CS46lTHjZRgy8w!IM%FiqY5PzFV@u4qiSJ@7+GWqRE05jW>cojDOgk^E&d2GQhd7P^$K|3#-JB4G{M+6L|Zddl)}E- ze)@F=#QtaIimTY2uopzeX?U1-TIc%#MD$#6WropJ**l1G0_Ytl(so8vGortki>fWq{ZqyRSg=W|=GC=G&V5^`yZ_uVs zxSk%4S|Xd0h!ylw+v%VhTjqL$H*F=3rXDMs)T9r^KRT>s>JYk)`AfwL?o^jSQgdp6 z50WG}`X0O$?bQD%`f94?;;uDNrZby-pKsuF>i0<8*OW07jm|-NF!gr2{{c*gv%c_l z13EgapB@AZ)J7hybsy&BJ~%Wp&Y-OouDp|Pob*M%u`@OM>C~u*|=9h(N80NHTJHJ5JDqWwUqL% z`av2Su^MpOz3_a!7<22?Hbdw(nWWK{P(t#QnrAI!_8)W5#gu@nTeEDY zI{1NYg3A$sM|-KDq=Rss!){n=6V^)y0%zu>SRQ6#sYn0kYr@6UfKK&5*pK9mvQ-TI z?fQb%;%b}MVIcIPn~)grp!ax#-4kSo-;xiQ=g@UqT|BZn?~4jm*wM4N?8O#%#|1KG zgg#-)YwEUqr%k3CDVEonnVY4*9Q(fZBC-EMx4E+>VHP)er!oNVT0}jqR!UbPE-d^N z{uZGSxJb>&&~Fm6QDX?&Me#?E;k&9rfa*jTGl2FQcCjlP;h6h%IcW$A4*DU1un8D9 z2=s*EU7M2;B_a%cz%?R*oW;1ozrrsQ{c6}EnZl8C5XQmmNUS)+9*LKQ0!vJa5vbP3 zt_LBInx7!qEKB*&&`7CaGA%`z~&{ zsf-80DWUx?5V&Qn9qdY^UD0~dh^_ZOi%8$V<&`BlNof88U@$;#I#uA3`5rC{YhsdT zd1+c#G5Yj~IdfhS4y<0KU38z7l{Fq9AIMu>B1wIJHGtAn$3RpvKDQQ)<+%|#Z%XXB z_1TQ@0bTe{*X^_L)<9|v*85;kOE9_D3C_~>Tp(al;ZX@PYg+PnM zzQ4!?*n+WNanVg2Rk8NJn8EG*IC$6s;a~L0zf5m!^fhob-O^1Fwjyy}@J8UHWcTS= zI1C)0#_SBMyj)d#Z2ooO%;`U79dSCk(*FX+!ymBm#Kd;lx<4!vchD%S`l-G|voDTm zZO0YE`q_zD3Em#{XX@_99LqEjb`788!QtW03Mwdm7}LWBS=rN%!YCb4AVy_!fOj< zAsY!=#WrM-a5<%Z*%mvY1DmMMWa&F+%=|D5%uWVA!5@#;0t_WbQnU) zK`9=6ZIPB?FNr1YUPE$5%Sn$P;W zuM<{yU7+1Bxuf_;rna}DJR&wCR()FxP0wI>BouSq9)GNbKIB@sViD#s>-zpPS6!S+ z@!2me8;9Wtib_j6F4wb+T3KoQjsT%^b{3`NI*qZ=b-1!G+1idY;eV~W3Afj+Yetyl zCtLA*^g82p!(t6pF!otSCExz^;*yc5+*RpSS+=&pcqjK4h_YIi-QdhD(8+o*u4eUbav!=(Fn1 z>IbCFuFE`UXKxbOTjQF&ZR95O+tZ>UE!TiA91YU6!nZH@0_pYGZR_GhsIfxIQC>u2`+ zX58GdVF8`SWeM5K{l5{c^&7y8R7qSG;-~b^GM!(oi@F-Dem-fheA9uP2^4RarZWI{U%8? zwA_88_WIHz7;Ta5tDSgV0*Ttae^q=vkbYg>{fMISf0pFCixAww{&=!cvM27#{`ZZE zi7WiR`um#qS0(aIqvWQ>N|CA}=_BIi)NLNKA?gac@8TU&RV`Y|y42GzA(47L0mS?_ z5M5)&g8}y9JzW>}=-3hIhHb&Sf=MywgT2=Rh8^$K@{M~qO2H>8^1(ouB#u1zSy z8w#H+GS^Z_n8_#z9Z&Aq1*xiac_w;$!v@v?!}misEdvss*<|WI#XG>=wKnp5qBrDj zT^?z-ZLf5hs3zIaopqwAWYz1DnBCUKNts@}E4nSbo!~KEi>z1|9Z)mDS6Zotakllp zM+o3XI`)j3p0mPTPlv>9Li!?WYK|>V_^$BgXU%q)Z>JpS2|Xc^R()f*doX7zGMQ!7 zNYnoC@UY{uo(Iio`#>m41^fL`o;oytb)e*<#NXjNFtryypTg{ZHeUe#XQJhv-9$a@ zJqR^<$rZ*mQnEt8-ZjK&gwTU}rer$<oyoNZMSPA4)ft=CYAr8$2@#~9{%4MyQyg0xR1gUv zBfVfvfDaf#Q4i-TnVVxC-YI^fo}gD&_mgfW*DT<3l=!k8CKKO<9j(bJ*C-Up($`nk z#|&ml|J1_AN!Eq2s->1cIJ(u|`4s`1v431mwr(f>ORMQ3l&<>|nr^)_E*?HsDLW|s z&8(J+g`c;x*z{4(%CcPd&jbVL@2?MrNJYYaFjycm>Ou+OCbaz_x99d#NC%2xaXC%WUI_i%Tf~5KRmK-rF5+mzy|V}y;%j)gQ}Ni8?wH6VYomMTD2At z_>Gx-Vum9c9OV6uX(Qq)N047ou#mWe1Ay=s0kiR!IQj_>G4bCCYcgvcW$b+d;NZgM za^&4pk8;UoahqQwZmGk|0Z$JiXSJEZX039RXAO1&O9vzycbLV)na-8=J;zFP6QcCLz@x7rjY|Aoi*NR65t5;%4 zNlE8m#CU$*U%Uvi?v1rqKU}=OdpukmTnwDv865!ASS_Y9xetL4w>}7xDlSjpz?zkw zOX`sZ1=4?q2JL{11`5mt_6?Ft@Rx8G8)`<|+|JVE8<)jFg-j9MGdANP7Z$rU+Hi0j zl&i|`e8Z%lg5}2D)FkVh=qQR1GIGTy-Zo=-ub(f!SsLia$KGlCFC4a&L=;8PhGG%` zXz{>#G{8qqIv_?wcE|FXx~+ubk({}JBB_x)D!CPq2}}r@EPzQNAfx|WJXEj;$x(P= zgy(+Wtq889I-Th3BzFENaBEzTN%_#&%cfh72i!cROm{ZR=}6v-W@{vmb@KIeGSCxs z3A9yF^b-B6p{U&xpl=*pDu~^^KjN~6s~b5TYi=~58d0*J5U{?DSzab0Q?YxA0kHxc zh$(K!P1Ei*0Xf8>8z0npR4q-OjhAcpO?Flj`zxc&Nj3yl&a~3}(&OVt)iIvJetN)rHVOq(H_gqdia9%jn zpO58%SjDrEZg)%g%XxD&@a5Z&+6JN8IiO0MV(<*!&iT;tx}f=FKc|$R2YW_xwejuE zT_K$g)y?Tjvorc-&1yMpSJi~TkL$@vTm2^zon?QiopO2GjaZ?%kbPTet)X)E{HRGA z>9tk~*a4zZ*o-+u@pv71Pm!GWtSv^EYz2|tJ7m?utfaO-GLunAOba;1melNbk*b4I zRS5vAlasx(@X#Ass$o`5YYC}Mv%YcgVoL#MRaT~zy-8r8i!6bj_V(VIHf*iDqdV5R z0zKxLZf31hEULI&ZA;U@P#-F%Q)NL{AiUTQI9~cf_iQ=BvrNo1sxczojsy8(S7DMz z079M~>;Z#u4mixBtgc^eUOg9y1J44;#-WMNMIA*0&2NGkyigWQQB9v^b$%hsj7a=11=Zxa>~$+ok=AaIqsphY$vUton=qQvo-3niaIuqK z;6e|Vk12p=-oRoie;?>?0@r}eU_P8VB$spdwc(I%fAI?~!1o#t1hC<+>8eYkkmabi zy!HZl+CbAT*_oX$30^6ThXM_9fR)QFOfQod;s?RQKy~wGr}=}c{@%R&nsckw{v?j7 zj9pMO1tCwf+C$@m%G>es<(F))6Y-G9)ZP_1Cq#sZy;Y;_P6D3LIP}fE{aOGRA4`0& zb2+u!70D%;g6Z;~d?n}=^ER2B)jmJ@H;c(u;l6)%5%VZ5i zd>Z{ZmD3?~xD5B%SRXgco6;9$+}qk=|8G=U;9S1StVPv7CU*DlP_inGru<19Pi|~% ziEB2--RT*$f284W;)UYOzJC3>l9o;rrEDQ9>GUCwxoU1_8C+Gz&LN?m|5luf_46p` zH@rPbp!VPAc)nLzmg#fOC_d>uY0Xu371M0G26nezU6bom09`HGTf+>iidcTwFpNpu z_z$ePg(cvEdZyyn=sHod=K^Ln@dAfjAExncSt(Mz0t@o$c~#wrxHbE^HJbn*1@`A> zsQl7cS+AYx`C{K(jkM3`j73XOxy|9xB}UK*d9q5cDA9H3)37m_Q&LO02Ni5@(n>}< zTT3^Awp4$2sT6gEHi9$~)i?K2pMpY0T$sor-f(dfmvxKsu95Fj?BTZGc{FN-?EZG7;lZUb1JM=fEfkVee79LlB*p)_ z01cHFFlJjk??eN^35TcjFc!pug(_YSmz4C(G*aH~H~C#92{&GA3Rx2F*xYMD~D! zhGaxhR#j?FB-v&Rf!>H@Q&PKMCfRC4Pu5n-ay@n?*(%0AF?U`h*{a7NUMe2)uch2I zxj~LW!8KoJoqJ(~b9U>~u}%oA5h#l$>ph94Z7ds|fVJkOeIqLyKE`5~v9@cbpDpVx zpmh)Fm>c11H|V&$ej%SQEvIm8auF`po>Ms3XO7u%61h~`(YQ!Bx0x=gqPkt{9`hz2 zQHk#AL~-_M5)L)>FG|kdVD#6V1;t!lITkBqmHV8~Yt{;ViHX&=iKHD4qv6n zL(feGZDu*fKPDv`F zWk==Ur)f;atcDWS(J3hkDp^_Z@hBhR`|Xdg&dM%H%suxI@>Aq9$VH&PHl+tY;&HC- z>6(M=k3WaeXmLqoth6uu+n>q{o`ge)uCkeuJigPMUYb^e+E%+u!mgxp^+zmqt&-9F zIC;EA*z4M)?Z4WnsxV?|atF_xsMF?zT4%D;WQthwQ!0D&^AjYI-xv`(B;N&py1u^T z;|qY^A74CKz(b!?!`SoS;q#dLgoF%Cq8AY3)1B-YCRK%CaktgcY=qzA8-0{B{6hk7 zYl<$we*k9pw)1kTiV-1bp*285mq@hvkdpGVbFRb z5M=Ng?;8f1uxeDEpF6s`_x5k#V0+ta*q$dAn@RodA>}kBS8|EMRmYQE!)X~(-3?C? zrln)E*R%=hwf#qgfKJ8c6{5+rYGQx+w}Q)K9oetZa#yyZ*?EeO;s6){KIZ)Egr03C z_xLF!>Oxla%rPX&C$9FdBMB^E=inqP3w&sP^t(YHKONuu`wl1q`vrxzx51 zxwCIW!{9J$UwY>;ST3g_Qrv<3`k8mEv)PsGvNL1!W|5|oOx||6u$E_ECE4LMQX{2j zICf#&;-XI8;Q3|_!aUS( zzShC&yrXf!^6ky%6f{4n$Dr)V9^CtKnivAA1XQH4`{Sw{$k=s!0qWK!($sWHoI$u# zlUgE2k(@Y!I)?8e5>r{@S4XReFx^XR%$BrV*ot!JMO`W5YZ8_+f3<-lT`hNjg)8vdHG)j_G;uOb6pT994pF5|)VIbXb1hxbe6A54^It5{ukMj3VypZX9TS zw>K7c^@EZ4l|6pxH>q>WlSYK$YiwxlTSME7dC5p4=y4VPasDNwT6lH8M9F9;=R$dxa^1ps2k%DklS|r0!ZkJSm0Cy*S7?E?dw)tba#4 ze0tG|vL`j(#Y`?8V`A`#YdGS4TtJ#dct>el3w~Z(ie!C4G<_BR&w53m=7f2?H))hl zU2@W?N)_e54+G1$-8YSy^fhZ~KKil}3iCaIwB>ll`sn1>`K9HhgxH`+asyLe>HAUD zr3ABjLg`Vdc!_w{`s(KH$_k2@#@O|E&ADV7I5>LlJVM2^luaIKs4++&lE8(YnexGA zJ#Kx?n{>oL*3oi0&rZ>P;;lZLJlvEpZQLQ;RyJcf{bby0%^~`}+xmrKJ#oZFnuUI^ zIVc$?!A#p(KHFg3f&~zAUwq~=OY}G=1 zK2Z=mGJ3z?*7$JM6Il5`T~|S$@Rl5FH+DL|l(NpU82@MOc8q83P(nYDz~H?3UO;Bl zj{9KEn~MFBe2hxop-7P*_s#u!XDECn!MwF5%t2X1B;Y23D$romvQ^neK_VhaEQ9>9 zusECi)BN0=-+Z&TuJ@(1e@wj7+?o2j)kGm>4*65zaShwk;zdfKk&#i}_=KP|`M99; zEB{(H+ilWiWrYR<0^p(5(?AOMp>|xBOZLHO(f!VVS?DMN_md zAzqz6KHCkSNuUN!P@d0#1QP(x*9DkUZZq3`HKy`_)wZ6sl0alx=Y>omR$N&|SuA_9M}HJP7+Sb~5ZT zq0@+02d$;vN{>a_CSJ3}ng6o8K`zZ3Qmq{xyw>B-w%*%&5e_`XBj}Z#zBha9wZP?d zWnu*Tf5v5RpouSrLq=9E5VM}qVz&Zvx4~{dOhYaBf5BB!v96Tb8345x3E2?P=};2` z?4u`>F1au7{aQ7(b}lT1@pbs2)>e!dmWr!6hF7@LwiY&!mzNlhGVpfh>bVK|)++qi z91i3v4yL$Pv<)2`7^aN=1c%klwOZTFL(xW2b2<($YGx{Ksx?}bv6Vzpl$jVqBA4v$ zlN*k{>2BdFYS?wLi_YSooU*(`11_Tskjr8rB1P^Xqk+RF+fu14jMn3I}qQ z5B4<5TIYX~l`@ZiJ=CdgpTl85tF>vI%SE+@;-odzD}yj3N28;)%m^T(o3oa%XdOAv zJ>9P;5yb@>oEth%JGSeH9x2J5Y!33%zZt-ncYKVUI8#@34SypI#1;~R#S}B9BZnO7 zET6OwdOE@nC4!lMy7M^69$cS1bEdXfe@0m996qsI_cWQL1ZigVpH?KK*8d1ji{N1O zFhXlMptD$uTuv2mVQv^?pVR{5sT?vItyR>Z5fKlptZ)@~J|kZvXt4N=Lk-KN4Lz=K zBjRBzwtU{T+~@y<&TGIHQpLn%_oqtK8+dkJi*_qIMT3tZTPgnqXv@rLHOIor)~N28 z2uwiLZ(>sK{$9mACxyi4WN?Rw5ockP+c#Gl2223B@Qc=M!k{yMql-MlNGmaw2)R+>+A&yKXlC+3W5O&uFQbx>VKNZu>3(v8V`qx9tIm_ZoK!A37ofo zr)9ZRdZlNn**l|wAY7<#E{^*CnHClOG*(Q0lQ@w6s+2x)e3cV%hJKtmKBhc6j)Bh1 znL#M%D|u0do(Y`t-1%?P6`Bg$wF+H)03kW-4^ z2tkL_)<~y+$zZJWVKp91L<4tOXSB$Jre0&Q+b$LlvsA4=pwi_vUsb`zdJQm!=pQq) z1!FPEhymLth6R7WvqD41c?etY(bNkW^w5l#*r_xs;v$N?=QB2WW-lBRI67K818aPO z(%PvtGkD5-aV9hMEa&G?E%1@fGiJ_ zA*451{fSGXIp=AufK;R#)sOB|GqCr4pA>-UYKH;2;4JgW0bS6S zgw?!f49I zWmVHz1ly^BRbz7SngrBp4dGns9J!GvZXkVvPNs4&5g%7iuGAj^Q#dfY&Ef}j^W>y* zg2>&sGX|%J`1)W{kA9wchX|4e!uf(*x1-&dbi1g6P@4fOG0rC ziSZ5Z;7}C><-MLUB?BdcIYWa**LX!u_t=>R7CO3MXk8sEE)k*l!UmV|p`wYLYo#?W zi#=*!$jD5?^zCCXxXA2m)V;BAQ1u27aItP#ndqk%nU=he8#=%9|vjzQB>$6 zfw8l?QHX`^8JJ(al5vhQXzAIc^`(iO;qmYhG14sZfSU4mQOv9hFRW=L4;AX!k?GfVXp(am;sF0KQ^!a!O{9fC}|LB53I zR`Z|r)seqwp_OrPQ_H(kbu?!?#c45xipKWTpC{0lt+sxrb$1;FR(Uqt!c;P`#|~z5 zEj>=hQl85%o96zQT)z|lXo@Y=PhjMiKEW-2Q;tn6%;8f&^K!0490DM+xkDjq;j7+mv=VCgCa7yw1t9 zL`BoZDWncAJmT)W&Jl1O_{$xPd2D{bgvY))TyfF-&&l93y_g4Hg z^UL5)eTy5etTPpeXvwCl9n>M){=4t{er0wj?yf4|89Vhy%2)@aTy!O-{qSj7ufE8 z(O=)PY4kR}XsalrzUC1Q)aeP|Ynoe7j|b3V)=|NA)1NNi=}Q%OyBQjUJYQO0Ma za6-sfav*V<_N2H1iFMy zHmgwIur1Of7KW$NA=0O{^eq;{=-=u|U7erj6s-ILShKV8Z`_^%KP zfClv;8dz1v?>laCdi9AK8uo@(bL#5$??Q22x0|5eL0kuP?mK!?$Y3^C;lONkfJRzE zPfBY3IWNuy7oR8aqU-B?zdS5dww`L?7K3n~E8OuE!gP$W&ma^jB|U{7$a=>>OZfGy zh|Y&K4!4HR?5y=TC^}--&M*cf@koxvfw zOtzdb=7zAGYlv>^7ZL1GWpuKE8JSfZ%fL9qWd2MlGQ=L8PB0mC+jaM%j(9wrivBE&OM0n^bjH#HCT%ShC-YnWyi{b6R=3SY2h zjfY7hhoo@T(yhEgpq}AbdISGR#A~R_+)irNSiPr9xj6BE_Ko9YQWeX|TVaG_w_*Nv zPPb9Z?lCMw;80~z<3sb)Km0lVlS}{bf|^yV_INJs(hiOe{uyBgDM&l)Jv~F)(B3#I zE$>V5FcuDOnxPf_L1}8jmjs3%}%NZy@3s6KA7F`X83^s=7Z#q+ck2 za$=j28IAYkKqR2r79zUItOpr1BGMo$O|`V_*_aLI!t+XkSWfE!C9AI06z!y!-69Tt z*uvv7Gel)v;7J_xs!gQ=3Cta;)p{zJk#GH`B&~7L5InwzQX@Jsh*$lj3HHW&pSg?GyVvs z_2BYrPGl`&Uswk1g=mH>EpL8jnSl6#+N*)T%?yTP;K>GiB3i3IaMK>Rp6+9YcME?b z^Bi5h4D8;V3PLp6y{sjJZ1UT}9=<0(9zRcF0M-15+(FhDCS!HNh}$Dd2)Xf%f>~}B z0t>&NYmbcC)9#(y9=qN8ft5zpbTuCCf>}nz4&H-0 z)-{S|=}2O%95D#c=96Yx5Dwj>bu|U`d=<#@frE!r@3tr`*sdC*@o9DA4WnJIHPg!{ zJy%}hNLzoG*sC%aS_)#fRn#7Nk*2X#Tp3J8l7`Ay$xHSL$^u zqk6G0g^=Guy+Xmk!xl@%=qsMh_n`B5z08blDn8906HpIVh<-b(vP;B@CCAOwJ$H0( zC~E4!ub#}9`<<)s_{CLODIfV}@5;`@q^tDtW z@d|in49`usX*Oo<0Fg4KWe;qJLkZR&sG7;?hQ_86A=?$2C?Q!{oBfs=wTPws^JK0S z?m3`Z`guF4w3G#}Mj<1+^k}LTu$Cp3GMbVtMVKp7XC}X>V@}HU^x}`?h&{|V0oezl zz@vE&7*R<%QunnAxr~m~QX1AYb`M;16Koa^S3H*kdNTWQ5#th|%4hnJDCB{$e13QH zYR#hzLo>Q(v$=rgN#1$jP=-YgVgJGxm$U{`<_0W!(~F&DPqS?sIv-yeS$%_{{-KGq z7BIWMK}UcGCwV=o6aK`q?_dDMdK!-j0;{>N*x5$WAP|so?Sudu14x=V0tAKh^dHSO z9D&SAximB&Z^3y`7xeo(5!kyOq3_=tE;iv1M15c~1Id^(Xbx3=q1C!t(>9;cv!;5r8gXHSbuDhcW^MPGm0737rbUF&+~obP3q!KV4VuGU*4>I$z+g6&@wVj*I?N@X-RMr3-&&KP$sQ3evnz*Yb zc686+isP!HB*KFmyh_{Jh6WX3?Mk{z%vt&Z5*^&tpU&D}r)ul#hF2HANJ?4&<>)g0 z3e0lCp~C^XB;*I1%jyUvBslUNcC-w-nOG%WWawcswnZEBrF1EQ%^lv4XblSTec4jl*eZ_cQ@_?9uv$#TTwE? zLAF^>FB5-rc zhNiv51r@hzETmdDP%)iWgXYa|GU4qK#ZkZ}& zpTCiCczd zvk!iQIpufU?vT=2vEnJO&@tA{AI>*?l=3>GgO6XtBqmK>kB<2k0k8sg&pWe}f8DEe zm<3#O!#jB`JstE3Sbnb@*U9;t;ksZ~o6g$UEVvDcP4BPzksaf{qP;;{Lsv__FJDxyN^BD(Au4%*w(%j`+O?HRiKV8A$bhZxGB|f8C_}nHI)VXy-`X(U-!#Li) zw3(Aj=C4DnhjWQ=HBa?%GuCRoo9B6m*=#`9!TWy*8RV8uR6WyBik}%d@`Nc0=C;T!t(_e6C=ul9O?w~F6D|}*4XKP+v7Xgm_2%>bThis zve00PLXyb|%^VTSgsI15abd;KA~?*|$76Df>JT@KBFnnLZzX+48b`+yyGhm#r}!5j*oAN#N5fGE)9gt1^(t>g5gre< z{u1(Y$!Iu}(a~!}V)UuM5M(?7dv@!J)i|R*a8NT?dM7P5-Dwt`vcj^Sd3HW5GF8Y{ z4uhF_TP~YmY~eT|EQ=?jF_R@ayWGga3#kJIQ(4bDgLXN0ub=+D7}JHTAZYGJR#mTC z-bss}f}$xC$Vk6PMLylkBW&mvKOZEHzwMmzxC>a zIgN^p^h5EAe12W>nwsQ)UU~x8|NGK29n_XSAmpxso8(o_Vwp?%v>ufOnIDm|}t* zzG`M5p^m3ogCvJ9S@$O|!U@g3Oj(Q6Unptqw7Y&7ABWw1IL2(GvQtW!c5ISWQB3q2 zjv8BS7K-efkEE=SL6tH)jk>Au^dRbJMfojzq3Y@LYF~S7h!n3NB%*( z)75VC$CnOwJdbs1jM-6)m2biJ3%5Bc#5e>EF1TXbHsK)dun_`42n_w_Y!Jpv@hg}a=pL2p$MG;uw3-~!od@A#Z2BQ0R(i5K$tTo=d7K_ za`>~j4FbZYF-q9!ys2l4$4nQ-;N)O;RO!}P%)!|(Ah7Wo>QPjw@3O-0)~z?2xj{C` zMn)aRd$rHz@hZnvR6)jTPNm!DX1`n?C4Za-vL5HRTP7VrU#wx`l}77vWY!)ZqjO}l zUHR!2Hw*7jN%;J;f9}K4bd@bedx>*yRCfWM2x4ZOPb4yIor4qhnIUtLfj^Ft7&mMtND< z&War@>qO4=5X)jPh(olqv`lU7N`?f=DlM(8nRD@`J$wifoBAdOuqi}cVqzItxj=nd z*`rd~gF`Ft{TTQ;u({-Q+#cnH&Qn;vi;KzFiyi7tR?+oT|7r<@vtaiO`<6{M@I&G> zH8VU3)qBlMwT+4Fi#$w`=c4*U6Dinox=)p>mVKKW`;{BM_ucNr#U$TN-kbi1}>ZcL99D^d;WW0!#dGUOZq2Y+sv_&Tkm94^zCsL@RgE-jc9~b_Ap$ z(mfL4Z+cQa62(b{iC)rRtlVKG^Q1nn`YPl%uOYrp#c@Pw$gr=nKQ#>i<*!=Wi=ag# z6&y{#Y+o`9t@II*&;`IH&1 z{ZTFE~uFGnDEfxFp#OWv7V1XNA*f&q&t~BCyP9L^$yX=FhR;Dv9{ca3k$#wt2`0A2V=BZQ~P_=NzV&Bq<(hG@Ec?=A4^5LVBzsFcweJ&M&bmu{i@ z^XQ%1eqAZELO~U4PUl7?6ok3Y!TM)w*MA~MVW<6GA{9HgxMG)a&s;nuk7ZZy0Z&Hu zir3IUWP2IiLP7Um;SjJ-V$$4Ztvm!KYuC03gC?5+%~@o@K76xlV=)kHA}fpK#9zoc zKmmK|=rl%1WfKm_@|>HH|50!dC17y+Wz)&?Jdfw~N|Epds(b5q$BW?p99iHKV756y zvef2+U_BTYaSm}-h&tbPhK>t5AF*olhNp~1U)I6x5|5J$S4zQIKU|`$W}rgZH+`Sb z4E-K>X=bADUq@XV?Oqe)37RgUl6laPwa^jF+JHP9y!$aJp|wja5`Pfz{LXi*M40+= zSutz*Rr@PqIy2d8s`Z$jK=NT7HoNbbTCSfpHVcwp*1my(NVR|Bb$~l9#b7M?Pfr|^ zfg8)dtB!-+v)E*D{)+JxBiqxk;AFvZ!pt43vyjwl^%798_9V6khVBPDqJzC784^hb z?`9p0skLmbDhU(j1JfP5n6h9rcoRR;0({w_(s~PgzxSpfrbq!onXrEG+k4gtX zI(9`gug3{3e6GQf(ood;u}@|f-*n|-^*{|)vC)r*yW#&h+%?&q5Ou%uJ|zTVl|?xt7~dvQ)Xo65Sp0E zG|+g9yR!5L)cAuUZWWAI`pwvB{4L77PQJBQ6L9r%Fw;mi~^R+vnvwG88c*uMA7N*??4P*94UDQ z)5Sm$g}nu*&I58d^>iLhFKytGMGl>MrkCNl@W`L**%31J^!as)v+#=-u$A3nxTFx%b~fG1?U1_B_N@p zp=cxkX@viVU1UUToXN^A4`eK3;(odygWG4p@rg3=u4$HjGp-as??h-51G&ay0#<=tw7nto7?@<)0^t{4ngTyzi((wqfNg}(t?BW zXpAcj*xB?nHlXZe- zXj11w62%s~0PVgjQ!TQy9ha9UVw1#v7uOf+i|DANpUmIBoBuq~Jc=Tr z8`_XimSEqn6)Gh6L71#}ly*e4ZH;hLvOYtLQXtAdxHg`^A}q?^{k$K2tDJc!*uQL; z=mHjno<635gY*eyUozobirIMiGZ%P`hu{$!3==+z7{ z8hZfbIj`6G%n0nrW8R)hAC-FX#ab4&H}0tuBD_B#iVJvSUgl4S$qF*Hw_W{_A03lB z1K?>?_7giDneo~*Tuuh%O$d{uR+~~ypM-WV&hErA-Q<7>eXi&M-ND;tOW zAP1h+s1|eE#ZUZ_*{9h~?ykMdWx&e-O9#qG5mRvp9-fYg^p(LZ3@6GYRWi* z^bM=qlC)ssNY-AE0q*ckF>~6ckH;$JMw}q*0Eqj?(kv#I@>Z;+yLxI?>dFjb>=R?( z{V=Ew)r&z8(VU!7J~wAf&k1Bp_i5ay)ippya58s;7`%L|G5Ob56N!jDsb)$Fi|H0t zwgywUltaQ|$$WcQ$*E%~=*hz(jR6rv!r{$OK!$)&Tp7F6K&i4^9!DThl_C;fIHmc5 zwOAojV&RZ}<}1O&MLOcMvm%;Ltqja2gea}>-kva_2c5zxNf$@~Ub{H_kyu z8I2cn1^i!Ievt&w=0Ex};gnY^>H8->j@b4oW)IIT9g2m8Vo*)o6rRVVZOw|jdTvjH z1ao`^LyfYlvL|H86}nJJ{f6t=jBDQWOGwRTOZbe&Pp6vR<$eQe z*wo-J`;MP9rRskz5(GuT6uGR{@mlesUQIA1y;6xti(b=U(zjkM4!wL>D3LT=X}b8g zv4%ubm$rn@RnX8-9u)4v0LQIrn;j$P+~m>INs_Ldk^mUwFIPyV6O7 zmIi6)gfAbSx-Nzr&+lL3yK3Cl-IHLB;bMrS$zz1EQ`FDhz|2n}aWmxu`!D;wb6sgegoF8P6-d;-c1y?6hy$>uA31uJbBW zcCtmMUYTm)0wP*4yz5x22xKj9Ol=Ko6gG3wa?!Zm&(b?U4!d`ba)>m(_eRvQ1pO&PpNkb@%q;9MWg&fa)(_}Ho9&r7 zc@Abft5**KUKCJMiU@p;w1f0Pc1t_VV@T)7(SwT@lLh&xrGj~Hl2<#g&({eqiwq!v zv7L2Pxh&!yzaqSS;(I1S`)oGuy50#8Z==FE$m!>RiU0~1^2E|IA19iZ#;umtiiwSN za3YWjzBnyv48ZEhUdLJE8!`q+3du&p2VihOisk!qDeu3DwMf`FNQ)?BZjQVooe9x` zZ%kMT1LJ}eO-YX;I5P*7c5kvq3O5CUH;uv~=O!?wlDr`Kg0j=O4S$esz1?{-c((0U zKg1)yrysF*lH!KO9Wlb*;4AvWkT-v}?nCc#q+B4u_H)-M3@HHkr#Fv=(S&vz%@l~r zl~@W@&ERl{XEQBEaHcrk{!UL!`G0G6+Zpv&&qTK`g=b`S2TWhlGYF zOeUL=E@lw@tqZ6MG9e>ckUdpP%grv9nu?AyP}OoGIaO6eM*>8C<$lV%n{F62%#$Sl z!-0-wW+KAz0MCTN5|z*9!+JmGy=-i{A>6)XsCDHpCbEwdUOwL2d&`OM0!V%;5boPK zq-kwh&~8pCqOZA4{Xifh?uRXZo3fB$QnA;Z=g;3R)I;>$A!G_UR#93$^ySh3t&vf5 zl`oKsZo?3{j;xcI7tB4&XW&>e7R$W)@qb#K0GgXRmR^V2WWy+uS`N$J>nXus0pUAJ zf%ZG@;r5YBK;hX_WKvy8$oHhj)o5w3G|V3$rh%=K{{`Q2rM8|)M3kJkeP8&d|A_J@ zp>x$b^h>BLbWQq5uP)^_2i|d4ydkzX`L7%Pme#GN>#7%>*NyZ_;PJf(TIwno>(Rod%YS)Ym#@N2ebHej0yBsLim z^{={wUoBiKb8yd3O)txRzBN=a%?N_RZ8 z(w2JNvATTM>+bIRgb-JBR`Rz!NmujS>1u|kNXqm>~j8ykN>;&^1ZNM z%D4xK+2tUU3rkkypw>Tk9Tnj^7i%LLrD9q2J^Zf>t^Z*@)$MatF z=3%M?JcjiO2b5g;biD)>@CR&NgMv@w*G2V3IT2Lvl3du6_4)n5>E~UR(xfJiRw^$zY>dr_#gzE0*Fl>pv(jga-sun)U zcov&+JFhjNqa5L=t!l5A<*gV*3<(3b$98t0&b*(&H|>(zB_Dy^?fP?Z9By||1g$}I z+$9xpQK59Q>RHLkvl<-I#n8Mvbofx=YGq+ZU90a`5) z&E1m#za>&^$rwxN11SSUqKT}6!CC?G81qEaC02$gr09~Vau)<|A*>k58l2Nrk3#d& z1r86}BJ%OfEG-6kURmj*WgbCgz~smbGQh>wT*ubIzQoAFp5=(&$YDR<$Yv+#Pbvkq zh6b*-t}$%@Z9}ctWDns-0N`7!94iOMz(1v3B>$T~G@M_|)$|h6e+a^!37o>s{B3C$ z76=OEksxFkQQtLqk2k$M)=ZaK)9{Ci>(N5XTCN8B$?jW4N|!KVY|F3IsG$?^R2o-h zyV@4U!>cd&mhf+)d$%rRbi<8e_YDxO87-I~00GUnU%vkj2XmWav+ym#?2&5bd zUrzxj8c6O-p4jd^RPHl@xZO1mm?nf_d;w{g#AVkGYqfKHPx0w$IZu5EE%0O6!^wKq zM!+hG^-J+p{e0tPQxq#(8!WEaG`rsBb;$a&19=YOy zF^ixKf^IM$vEQb^Vb&tZRMH#*Ssa%9G6x()abe$ym>EefZu}Yh_kX+H<~GdXd=m$- zOc}N(KetQEulN7?D9muBgSRV^IgO8xZ$i3jO~-P4Y)#8F;TUC+6%b?^?*9OQjfPXb zs_JRjJaoNhalV6aR(+-`F5LQtV_V+rvP1vm@pkEv=*6CC?*+xX3?a?0e>$<7iymH6 zV`Qwfdp)8m?JtOC`JWsZOoPVrmgT8d^Jqy*S`$s4R#)%L!+Iv@!?F<;jAQI2Ff4X#VXgs8F|LtXY19*9G$5b{@!X;)J~!IHq&%ZgqWB? z$;lYwnP0Xy`@b|{Bg=?Z%kCSA1o1I!>cW6OrD*j-7e(3KmxbJ+@~6w=XBT&Cg;9;O z=GKNn^XSHUs||P>1kDPj(-f|hoJ1rA3uG;;v6M0+00HbJg~s1SegHlW7fWdSm-bH5 z>{Q3TTIYukkI^pPjn>0;A6wDpT976MPvsY;Cx=I$lh!ac6B9c>3dg6}=|Zu!H+@AW z&f*{TWqf*xn0FfdxL-8(A_e5JMg4(akqyUB4AGPM12vIa#$ zxH~aBXA!15*}MTD^m(X*hXOmyiio!3N)2^XrC)ArBOuM*$GI|&8=<3`=gLgQmIP z{k)UzSrky~ps0raHwb_Kj+T|u?yt4Dd^O+e{{WZG=cfn!tGTOrIg#Y~Gk!10|3pyc zY9gUkH>PPxsPziz3zPPW(y$=;~cQ!H7%>uI9x*7{$PT~$%+*x;a z@w8mC+aMASo;RNLwCwu?LGlEWG*&|950ve+*wd+;r{xF*5)N>3Ek{OK(59QXXAOzF zFEg~TWAKMY=uEYR_+xlM1$Y;7jympkCB6uk2P~IURrnldec{j4~Qy@;FY6s};2|TMWF%T8_j-oj3*81_nDn+O7^sbi`;L3eT34+ zwu5#gPz9~Op(%@g$+|%Qvn`6p?N7Ng5JTgthPho}8i~&h%$U+L>7_;^As#$A1Y`)> z(yM~WGk6@n0l+177vt(DV|=5Q{8!64+7geztHL}+$k4RN?fK;X)b@wk+Q~$Z;xKU1 zs96r}j+PFa&s`4qiskldP*{d=cQoGP>WW+P;Wawg_vO%G!_y6JbVF}2XgNBy);X>;ZW3vZaJep9O`bofiKaP@b6aqtykH@#ZH> z&M^cyBll3_kgzZeZ0b$HOMOhb4Sr=Y2?-1$tkJ$wD~YJ{6(E3SC_yaO^BhL}!gnOB zEH^H2;f^{6@x-V6aZxNR|J;-`^@KRyJ`m0MKTJeXOk5j{Gu3>p)gO4QiQgQs&lmbo z(yXOPCl=LZZ;_RrT%7GjEZCf0SK`9T4d@>Fo*6Wh{`>WR*ldauY^{4MpRz%IF2A64 zzN-Gk(e`YapKOR~AT*QRfbr#+yVm$)4_+Y-Gt%yb zf0X3aRvF&T7IBYwB@)seE32d7$pnt%2DdGF7;#%44h{_uqYdqeEzsSb3y7pq&Liib zZtjvJN7?dw<^L*>R7^@uoz#>>uH6wMn+{m|agT$bUE_rk&Gqtc?aqHUr?QR5J3pdg z7U$krliGTDf7y#PJ=i+bEW4GIv@!mKdgnyB;e2Y?k8rXIGD>9Vav??3cAFaATEgSW zku%qez?;&VPJwXed~bv=sUn_-j1%q6YZm2iZkD%KgPXUGfDC#YLSz3~%bV?=!h#YB z;?p0wvu-&V7aU9sLOdCz+tV^;5-!1UrroLF@t~8en*<3Le2>}0b0?YDnq}!SPW5C) zIh8Yqt}ROI)dA1DR{8_=tqV`b$z2Swt-A<~`*o!&eEsmsu_ugIYrP8F1(P|WEdl;Z zQdk#eD=~+1IYO~`01H^ZYBtm)7nztn2+gz?m)$~uC7!s~h^!fjfKy|9Gm&C|-Q*rO z44I&RYr6oK?o%t8XDxyu5pfld z&zH2_JHTpkz$1ZzYq%V zQE@S6;sHu79tjXVPh)x8U(Og9_0R`(9htUb7jZ6Ez*Oy^U7`&?Q%;yAIQX~dSgXU1 zX>?PsySC^&Y6trgVq1N&(DOi_f3M4czMQ8jGE#zY@9ja&k799ob!Pf}?}u;r%$CX` zyg50se)xRhNB?w}V|F)zLC6Q|Xp|%K@!%fM!2sg$c%6KB^4N7^uS}^ZumoZXr!>RRJ8onjQ(#pqW@3c8y7eX*Rp{; zxLul@Z{+dR+(}|Fs&oby!soWMJa0<`hXQ#Uxikt%1jU^Ft1ioEj$hz_9xZ=#{?Fw| z_+)Sssv>?Mz1HFt%8+g|JRwkg84x`-IxIt_*=|?pzClK2mp#N+WuU;Nv4D$*_cAZ5 z6y4nH3ELip<1;cc0_cco9ABHDg+ebBY^D%BFgVl+hiDjPq=GwkCzo@tc?mQfl+o-q zW!Ii@JcX@C4N1*=A%=+}GCkC=K1A6WYOHzp<6^Om)s()*!cSO-?pgobmG@uz%r-D? znyM8oRvVdoFS>n3jN98cysjX0Cf^_Pj+X203_oYR#ZB4l4!7&2$dK2XA~-(3v~KNA zMKzug*W1qr-j4H4t^BEkHD{abg-9YOK7YvMfYv7JVEQn)6kH^dnlm<9edPMqtP%xSi?g4(Vjt8XQ0G zj+iD(R{ge{p7r&t4RWO0E9D@c?@rv0w?1i_CGtC~DU=%-9I5>v!1Bd}j{A$}ulCt} zUZ1MCD>v?DcM@j3*726i2@LF#LQyXoUcepB++wP)X@sHcX zN52U*!#}^z_<&UN5yo5f_vzZovWYyFkD=tu5wB_Mor;~!3E5$`*$!5PHQVU>M@O{H zO8vkn@2|%W%FOVhHrTlsF9NDQ={?bRWvG6CG0n|Q45#;2)%4n9nkf?v(C@(Hu^#8j zetYWa

j6^)hv?NbIISJ;jUgX7{cP;i%)} zsu}2;I^u@?aRG|97Pgg+k*P~81rM2r+B!4)z=-4T^!^^)P)>4gV4tf3CX5Dy$EQ{Zw_$3#p?%f-Z4!s=84hog4mqcXpH z?&20J<_%qESWzp+P*@y&=#&>6#u2sv30M9q09x{TSNx(Vqk4XRk@kPwZq{N*bApU{ zO{C66@2iYu&AMfe{Wab^0}!rheqWh(AzW4!Gq7ONmW<+U=Z;>^U#Cm9KxN~~%=iNB zda)|R`rUB;TN2LJ+JeCkA|0qxWm|+=`N=#`63+d9@)ym2=ju7tRpETFURTJcr{pyE zUj^ariOzO;6f)3DLF+1zp}>)Fn7&WR4z0#z1072PwTs3a9e9%_^vJv z(o)$hE@Vv)Te(Wf8`WHe%_;__5o&-viWjdW-I(wXXQ*`?G4IrM(2RK9{I)P*d}j75 z!v$vx&@cL6!wyoOp;jsKlmgJjK0_6f4FqV=u5Q2z1L>Lo<9GbQgL(~`(sHYoI5rw z;s{Hq7)6A3zSl@Arq@ck#-Rwvad&g?9UM(3UiY3Ymn0FVe}s$Zgnyu|Gmu6O`*bs~ zsGIWOi80d=e^gf;kJI6ESKMJa8^mWm&fdtBGpRdUTsnG$-cI;Xax6q)Y`B~1J zt6!F&>6=xc-LQ+jxo!6#O6jHP^nQd{!~xF?bF)w@CCBksoq1EUHv;~7Pnk+-^NN_9 z^oObgFcUs;)J~NU<}U{Dv9^*&dXg;)uLqHg}wa}5l1`SK%-uTle3rUrz)oXi7>*XCxmi-Mk(_GWs)lZ~N9;!k+ z)$^6=JW$)%d)hU`KAe}BVOb+>yQMDagVL~UP&7f1LmTesTJFCmx<90U>TB4K4&<4o zeWX*79vHr^x4H`{Wf`566;ZLni3)5c9Vip2PuC@@()<=?736YrM_17)yAkTMt1h%# z(VQj{`0Ua&%+xHQ^QT!7Y*2{3W_*5Vn~nOU@P&}yC05T_xR+uPmVlv)E|xbPXtvBC zxgj+E=(9E7N=4?s{`mwwq^T=DV^n|M7wPl2ft8K-qO!Ie5bTVo_Q+WMWZue4ZOeQq zeynVfNmM_)Y!O36yEmB`ybKc?BWk0#NXjiUB0s!_h0h=NC?;`DMKQ*{$@c?DkMOgM z9L&OsI$NT?mm3-V8L~h8D<%X$x1i1!boOTgS(?y}#8jqC3b-g6!vCvT0Q4)sLs>!n z({sc=stD6z9P6p}ZIOHq9Du8Qpg96oh{Z*;sMl-%#-~qSTib`sRqN^RKRyC%u34$Y zWaN8|qs9pMEt>z)_J~qs;0gkVooC@J&~f;K|KmV1F%_TrBhA<$!xla&h8m8iS9y;REd zDsf?_o0wGYW^v8*`p@0m3?AHD>`EWIy0&^``vJc>JSM=n;aDawOld}_T-<13ap{x) zr)G;oGVX-xt={#0O;(Uo_N zwXBR{F6xy?%`sJk15)L8XCKPhQ&%ieQg4@`Gw|YDdyDIT#F8|~Sw=^zx?32Od>_cf z(}@#&9^MZ!;M1WG%GOrxj`+ziZ*H&c>8j}m{DV`zdp4J57TR4a3QvjJp^Rc#FR9tC zBFB`a!qa&Bl^+%k_PxWLh!XY+E~prsGjpmdr4Be`WamZet}7MQq?kH<*;nF2^Z z``HK;g3}~U2zVg2WZoz^!7j}0ka9Q`o!G?MAz$HDXBzmcQS32{QAYW!Aj8BXJr;Q? z0Mb{Xsgi}1_X|0%m*Af#xj>Oi2*kVk8gi08S?OvZPs&2TV)J(h(;)R z={Vt7zC^rQ&adr+SW)O-v+2kDC@u|nCMU!=CFvsl@`FdsGf&WKQ5xrtOf==3M_trr z8tbR{>s;uQSiIhFkhCn`<{O>?5=O*HZ_1R=y{l92s^(ZVvHo24;qIo`*9Z5@!I23A z>m6;rHY4)OfrUnTo60|dbdTNxU%ej(=y^gV6hHf*n0cA#+yxU^%mU;4pZ%SP{$4tRSi6nh~TEN~k` z$evk}cPJBY@Cw#GD}9CxzY|KzaP$uFfJOP!aoKzmE+07jPk8dlO=0vJJ!{T?kTg-7$lPSNAD?U7eBb7!U$6Vo6!u3V z8oe;Fa&eA_e@d^W#U9TGtgRZl2~Hv>BEz-x}&n&K7iwqXVza(kPnt+)EYr z%fB_`1%&zD34DFX|CfMGrDLrBzeBF;Kd=qvZ9Y7~y*<7{x0XOJ zg+$8*&trK!{!-%gshe@n0A502e->2@U7%$gprbm8toz!x)Ke$d}T|qEhJBd9di3=b-=+lKC7gX81d|TI>0N zjYimz(N3nBP6&L1wWnt{wEx5O%e-4U9TVgJ!i~(C-rw!DetL&Bn=N;@FHO~RE=3x8 zn|mTQ)$3aZ4}K1*8{pS|k%=|_{+to|BL_1lt9)Jy6Ju)*c6q%w{iDf!r#Bm+z4YoC zEf3Y}2M#q&Weruy^&0|Ajg6g+`6!x9=Ko?|U(%1tG3))W%?w_HhI{z~vc~x7uqEG^ zUN2$B$c{)03{wVNG*d4I;1g3hykdFI2tG)XH@m#cX$vcbQ@=|fX7ur+BG_2(OXEDR zvmckF@39AmQHB?_l}$BNc0Fa>`Z1? z=IwN5#dfJG0@tsLdqk6|rs{x{g-uN|)|Z363WUMo#kn9(f?uIC&2g$6RX{wjHI zi5Ez>MY{24u9ryNlXZw4Z9>6{2m!4jt^=zjI~eg^m_Kq}E}&PW-|Kf)hegNn;%|ju zJg`OImK8h-5)HX4zTzFO-1jWv`lh=+8PnL7fe_Sc>i0T6dGj9@2Gf84`X2PL{~4n! zHk1HX2LV&4cZ`gpgLARmy|H;RbarfZB9e0it8OQnmz%dt_T&hf8cm=Kap#00CBLZy z^>Rg5HznabTGodblXC_8J)a(@TU;#pyqe6XW^=SqXY;tJ?;tl{cC;~xhWV?Rw~x== zo%3trVtN>Mquh)X4*lYCIwlTh2uzr4BY}aDUrCMf9b+O}h~V~+%wRHkpcX-1S7vJ2_IJ(EDo z2~(?U-Ukp%9T*;{&duY|B<)i9Jt+W8NCnnQvSPs6qv`h+C_iKF&u{-e$E!*)LZ$6q zHvC+#w3Yo`IhZH@B%UXJ&X=L%<(Gi6a2vKcu}>?Q8o^~$eEB2t!Wwufw0t+(TV+Qf z$-bm|O=ZR2vj28?1tDrkmfs^bIn{#>?Nlm>u^de7m88bdC7Z@`D>Y9P)z3-9)Wuw- zeJyVDFbqZAaZ(wAKLls=g7Fn2p~DrO)f{Mb^x{OIbF&wDg@twUl2@S?@Y3vumi*@w z+|}g#Np0}bH6n^sx=t`SyF|Q=*Cb%!0l_RHkT=64d1nu0iH6U&@FZ-8Qh@4gc+y%u z$|^QO*6gSrOW}6gRMgNy-4%rznrS!60|Ys|D%B@ct{7-2SRZG)t#L*yS&a0Wm2hc5UEB^{qfTmk|H40=CA zNw|-)G~fE4xoVyJwd(Cn7UjC#Te1ncm+kD6uUl=5{$TX7hhC;dT{>E0x0Z+LA{X?9yW z_q4ugJZK>)ofkI2&16#Obc-wz8z?MiL8X z3Myu1RwPP&B)qLD3H;dV_tzE)bD8eFE4?b-E3uzq2t@vhQ;GjO5zf&zI*FT`d9UVF z6{oB0C0p;^_FD`-N^51x&D2)f$;eokf~iC0rL&|rnnP1!S1~C;P1ZXaT-5f)raczo zXZ8wf3Nk%Db~kl)NU*$|QSZp7h3d7wF!e0$E^h{c1v?7oUY`o>hRFWt z4G8c(%S@dl$x4%BJmqB}>vN&d8wJ^y>fZ^}R~mV7NmD8Kww*9Qww7C^CzD$OY^)f!F$~B!T&t|^sC?Ibwr2U7hjG#)>GXp?V!qE0rJSV< z+}|8N=azC2V(`;t7 z?~X;vTKkqZk!G}zq{3mnwbVADxaY?!5#ECd4n)y6Q?sCz&Gufl9gRD&;hb^rDeu;) zwmEJVt7(|NwL89y>SXlqPP!-@?!hXM=^HAF2VBk?nk5ugsyGN{k7r-r?Do z)Ti}e1|`~s0bU%V&9Z1;(D^r#=adOaVav-wL0;d+eU3a>w=gt`Aj&Rz#hyJ?=(5lv zcWy?r{GIug+zF{=I8WAhPo4CzOxCzbh&fj3m#;mp za;|tr59L1QQPvzQ%e4L5aq<^FE>%yRx}!hVqzz0Am;crRUIEY()2cAly+=;d->;{g ztY|Hgi<*>~QPi8;u3aT$z_332h#bu}RuN3Gzx{nXnEF!n8c_1uSh^~vbt|Iz zJ_fvMhP}Sm66g{MtLMBYE6CtCrUVQK4z5K~;6g6}CL694LzChE6gK2PxjI=2bUZuR zpTz~s60GTXgCPsp{A|KZeZHw^HdHZ{gskXgfh|mr-tHzO-cX_Kp|n5LgfuAz+J~l$KjI1b@)+-s196EZ z&8#rdb_UU~*y5Tm68j`kXoMi<0F~!yYh(E6X{23}U1M_jLqrSn1+kOTCJD$OuupO~X0$TD(khY}v z^fD#<~4>fBre%T;XFTC4uQ)NGfv zPS->LlE_w%m>sM>nj??;V~53pp{yrznwPx4xi-kE{SPEUzxe~?0O>L$Z3cUpqW zt57<#;r4xZ)91#St=~{3A^O}~ERyW+EOvbe))$LFy^19n;g5I*9Ylx<8p`VK=r%{5 zo@FU6um>mn-W3%U!8Z6konFo}gKDsX{riT7n}`N9oWFg4Au?=t%-Mgo^mwtF`sfdS zz@f0DIh9=tG?lZcT%rp3H6SYF2S9r7V8vAb6w%&GSvDwk%;hBtt`44@ zs2C_6<qm6+ev%o?YhCF5^n}+2JWP0@<_MQ zB(0}2iG}vI$Qy>nTL1Yc%8G{sxALZ|*IO2>vb%xf(a+xwDzKdm3})8qB1xYtdqnv> z?$C~#iQnIQ*ofXu7=(QCM#o%=eAm?_PyP7dhK4w0L^kEoTb(TRv5lVHQN&7MM?#*Q z(HEH_d~llg0FMvhw#4y#U!4?@!c=g@&93Z|c|5W_8bwjT{zNw!y?0i~9I`9OF0Aqo z#~tr6ZzJM%wBlGn1qGzwxwKVJr6YOVDegOhH0kY&0>?|f6h?a6Y$HFiFoIwtPuC>`6 zK&%r1jR_QlNzk!Tq88&Sy^ENSD!<)0(ez@SvN@dF9j~rm-Yk~KFmp>0$F+jGz?N9Q zsJPY50e5JE!L;Y6Z$;W|ojmm?VXDUt&8>F>mFueYcRq0jlM)vvHJ*=1z{2`{dIt`) zz?n%sWeP$pf~3z3Sb3|nNKJIjzM60YsOqWbooLAh`(Dl@BJcwjD%UEvI52%Sn?o~o z#X|*A(dIHWiVN|Gtn0@$=r(u8ou6TNfX|tES}U`ZG_sHCOMuC9zA)?AX$~PhgNB&S zAFGnBBcl0|*`)9MaJEe)&czTi-c%GRL6^v}E02E8O;s^ng-R>cY}p2%*SO1%o~^f? zU)`boud}{>%@KwQYS5cM>_Wm?Jre+K?H6_8wy)bI0!xVjSvzhhJlYyrfJNx3=!+t8VXNfwGzbMR6q_Or?D9*p1x!vZqj^?frm}!XEK#}6o zHk8Z^{xlb>O*`40d>x33u#~Z)tP@4R5Y9)rGL=B(v`Fw&@cokbii-th%q8hE;`4l* zZExUaTDhNDpulb7+Gwu7?Cb6)LSz$;l_z3@5x7%J#Hxvlvk~@!mYka3kO*11e*Tj> zS+p8s1GxNK+mQZ&?yjT7*ZK@^N+8R4Vpjud7+hFECU7A;&R8}vKl>Hysc|w!=nVSV zFFq!%sfwVZ)3Rk}QSG}cEw5tT!%Qaco0?}5C>g4B*t9hDeODYGb*sb|+`)0dn;Wog z{djvkq3YL)fjfukrkA-idZ(E_A=pWTyrD~8VP68Pz3FQ{aer^GENOkM~o=mzBC3mt^U^1wu;If z&d>V`UUoqF5WoIVS@wq!ncc@LYRw}@WmpWx#gcw_lpb<2ETdqKshprI16{T$?qj5; z_I}?R7E<P?sPK#@5 zbHnsy4;cCFZ6r?8!R6k(;T`8J=B0)%9AWr!V(Yp3;TJnBE!h>7Tdu|*Ui1X}CHrzy zL*Y1x*SkNJo`Y;pg8T)ks-9Dele-8N0qHfrpov28cDZA@$@6E?OvvCYQT#I|kQ z=rg~2|99QHo_BdUE3?*~^F3$p&!)>>xiu@D9NF!wgN)aApWnx1nC6@RGU|HW+o3s8 zd1Fc!1#a)mAi`b8S#FGl)wuBsR?ND)Qze`Wrx}_V`&%t}s^~N1v%9g-^>dw7zTWg) zOW{nu_cHiu^(ot|g9j%=^`Hh=EJ_NG(qWpAyA-@xBGR*chmJ=^@mgGTGcLdSesdd~ zT0@hqTiy#5osF_OG;g1O`hSMqH~k>ePag@_1x(Lffe-krR68=3LC?=Gvt%{65KBb< z5QpT5%|<&YF%d0@PP?(z<1jj%Cr}$zz~D9*NkX$OQ?|VE14n`c zA)MhGStQ5F5!63K9Ovq=gW2<%U2-H>T-VD)TI4QCQ1I)`PJMgTnugw?rEI9e34jO7~g6mpH zqKy!at#|#)m1%TzwRVqYe!woOaW1!QpG|#HUp@F?qqDj_JDu`L!1oO*jd*uNv^HZj zzCFQv!SbNg=ARt(eS8liH*BcYgK6(jF$k6E&+=~TwbmS^UKBx}6-#mL?qH_zUZOp1 zlRwllCTF6yxa+oTt%7Uc%3nG}wQ;7oR6~=Uz)lEvVAm9FeyvE!vPE@$cdunNql+Ah zevLf;4KXOM-R9KH;*kFj;(7K!Up}GUhWF9lWBt)9OJ4TmbdfBQKMzu#bjCRI;O?Y>LmhH^r+ViUHiZ$20TT-&#^1bJrz^90V@fsU~Q18=E*6UFAC^oB}osq!w z9;`;J(19vUY!eR3uJ5pub2N}Z+QzV}{5-FM4F)7Qzg|#UN%}Yu_JNdEj~0?M44>8% zlc0VPzy7H|FG^pIgEET$_F%Tgsv*{eaE_8r#NvX64Q(=v8>FhFd=bs;%ctZh4qC~w zL3{2UU1~g!46DQRXvD9v#P%OpfFltnB(ie;Y4tHdyOA|I2G%jP8#^d|dp)DJAZ-(S z8S^X&ZO@W89+2JeToP~!u?|xa$wmh zHM9DktN05(FOX3Orer;~9o;kWm z-JZ2FV{Xm}y;M!CVO*ko%h;8Fa8^!1#XkB}-Ol0k#0IB~K~c@!kA)(9NQUOup~z=+ zlLnPcJ7c9Ko!}0v;XlPND07mK0N{TB=G*_^HVj0!^z+&KZ_g~OdekB5KpoD12>Cjd zQ=v$GTj$t17&jg-o`!)#a_OL-|4g_JyL?ij)nv)5KSPE5+&PqzzRsO;I~$7p0SwWi#L5iK9v$8RS!@@uCJijTWv zhqz?YI-}cnt+0*_0^$2N+*XP9-SYF8wfpb7yi4O*_R;5(z2%SqrD7LgZIF?wV!{Y+ z{tGpoK$Hm_%mYHtxXj-8DiiGi>V?1%3Ehb9c~j`J&`|^t{uh{QAtVk_N~w^>jop7GZx0SFTF+}G?KElvY=ckssc*j{e1dI?BxpP7 z7j(CEc7rJ5N&cI7{r{`Tf@~aO+#i-d*W0cueRrObq3>o$EkL01y89>&pIdF`f~c-6 zgrOnBhBfiq+#F8xV1)S5;$p9 zQtLg}e{N*8<^>9!7cl?BV&v8DCYu7*3L0b`-1E{^XC; z2LsJ)ZO`!Xc;VOexJmBx4%Ocasl6*?{w5}2=G*FqWZWCbG?s=wT0SerVmD$g)-{(< zEX0fb;pJ;GPn3DCEwv+E0W$s#XR)!^J1+}*k|LIC%SnQO@&tG}22EM*7J?7PSGSL5 zV0envq*jNAYoR9)D(WWpsM zRQBV{Dm_0Yl#&`7FSopSQVUt_%X0eSkAPx-=Fx!sAGC{ z?BktD9&Y*E9g#mg-xb?cZ|7A{&bA!dJ4*Yq1)!hf(X>f=EYq1ZrfC9WCLazBR++Fk zHVw4GP7%)5QSFXjYoveT^S~PJ%n*dQPHry|!AA|laeBz^XPBP`ninhGiCaEXA@J17 zBzNx4jM$Y7RVkgGhc+)Hs6KM)x?~@zvjg_|;!5^g&dTWz1DmUa8`Ot8-eX&EeZlqj zXtZl)b$0VJ7nZh-eEsC8)c34{*VR6)k1ycyv3;C54R6PBfH0ER;Rhn7p z-%?43!A_jC*QAPC@pX(YvgWTX@hx5kUagyJ-$p6uHymDuHo)#QFrkvgRcPZcQ;m|M zrA=f-KOURX*Q{JWXqcBG2y@H;Pv~Rjm94dEZUA+P!~AB~%w}JtI!k_+;b5T~6Lz-v zQ5oLr82Uas-dHb&pyOyczglRMe{$-uv>2Py{^xtPx8KKP$Iz{CFcUFvWG!kRHY!t^ zgJEB2Dr02WE-VTzU)uGq7&Dh8bHacOnd6+!Lgj08rnuEIjqQ;ii6|bw-pF*l5+VVu z!M_b&L_*46ry5*`6Z5et>OzK!R1FOcbBl}0F1cxN`)qS+It8saIE&TmyBC!qMz74u z6!b=FXQzQkF#}z~6p+Hb|Fn1ZKke0z1IBcEery|WbfiDFC^!V2s$U2JsG25xCPWnJ zF%57?kgjhQ2YYqmO)#(?Q^&p=0OZwc<%Qd(2`SC~qMPwk6t(1P{MMLp(#2>h>naH0 z-6)`gi_Y4)c#b)uYtmg|I=B@Ov_Z&@v}Twvj2Rx?RB)*Fhs$;w5S?SXliKMH5*nGr zoJnoXioW6Wh8-wYa}@sg>d_LuD%w=isWN6Wp{!YxSxgrN?ycpsD_*oWolJKR2f%{| zZ##s6tU6timN#GTXz!RBuqUG9RXUL#)xky)!X(ibP86EjFQrJu4Wpd#j?uz>_!B9K z${RT>5U1E9(*OM12#E62EoB*A?~aSd`jQ#6D}S+FvXfKPQkjqpr*qT-Pca%hnlf!x zH_dL7ZAgo)6+f=g79v`$8sqAX>cRul>#bREQ|t`iXQD`HrPaur(jj#DB9}`V(u(ye zuLGNv=F9?crL30E@G989N-{O^|y@FeAY^R8BbmipY+*zoArqgN~tW@>H(_J+@oWl@5 zbcGyRdZ#1CqO@sBa5?v~U`|`a*oK21lRD2`&QFi&+ z=OPg4bTZOmvWD^ocn}E$70v?OJr`&pcu1#@yLkdc0tRxn;^00rdP9Q+95@=cLRAyf zy^{KyG05YU%~>gMqaSt#bKS-S$MdEaDjH2kHO-P@w0fF62g%Pz_xk=vcU?Xb0Y2oz z|BQLayt+P$?2<=?6p4?P4E!Qu^m?C%o zbk6hGlkdcVr`-T9tfUd-^DqwX4~pJ!Ns$p8SmYB7mCY;4LR_8eRKpFai zE&q{rL;q4P3A<~S(13aLKqJew6(WY|2is& zk>D%-!rF*Hwp?1ab`Y%ITqkMZb{R%yn2=Y32&h2FFkB#mrgLG-uDtCb{T{QGDa z4omE^VqYry^%vy<{_(jQOc1XjrS6wBFYU5tRIEt5-;4yEg7x?Cc_tyBf*v~8Etctj znsLaV;jeC+AJQK<}0W7v4aK_45(F$WcCL?>Jx@q&wVP04e%YYFZ&>! z4ev#iUEJvn1JT{jcNc7be7v(&SAdhew;A1|@b0$17!YxLu0k2bM1z@(-oA-N5lAgH zZ;M0|h^Q=S48$NnvX<85QE9?=L%{Z0W87md$fI3d*y91n>_i{y*_bu^?2^H&D7Z09 zJpzYA#j7qZ>OwM)kkaB_7)QfVrL3zw_#BQyuiq}Ko4M90A?pIQFFFqv9V6qvLl=S- zo#M%9^B6q(pDhH0m-fH55c!>c;UlLi^BV_7#}>92-u=X$2; z7j1Iu$-;sP6#8UkWrvVcOqv#Zu8;`P^kXZ^zN*(-TMw?FS2Jp(iKPlS!lXIn#iifl zgyH}?w$BK#x7W|KKH=~Kl9Taj4%y0N{AX;%`REqrrW-*qR^?QB=RpH=U(40to=Qu? zUpe}BY%O^l_>x%(TLL2H6lwSgbU1q{>hk*ijY!I~1baxr1Y( zu{;glnbxlLX0quQy7Sd7)63xW04Q6z2MulQ*$PdT26vyiIW-|0*snB({EQmbu+Jz* zo6$pYlZ-ZFEVPmCaf^9_wFW|zw|Ri&+jD}4ixH#453f!E1qrcQ*4hTq%^}4CM?NdR zI8sX4^!nS1$V{#b{k}=ieny4IkYp`yk{?6CX4_ew){4uC&>-Rlb$G3~IAN^;Qg5}g z852a4ug_#DsymxGT@AWtNxom)d|7{u%9Ej`*$1+WT(F5cS0;T`%bzKF-OcjSX@8k6 znpLj9`_@gv7%11{*WBRR&5^@)&bKnv-hgz@s|Q}V=c3isF938)*CXLbRFTeE5;&f{ z(IH~!6IH$?Te|7{bP#Vp?CBmJ0vfz-rTMdcocwJWCP2vhGb+}ay`2qPA}M^BJk z>#UX8Fbzp{N&#wW2=3nD%~65Yb){=OPRDqG;eaayh^9nUF4mB8-D zkQ@8Q%ZS>JHVuX*a8;7PxQ-Bbsqr^pf3UrBFg4yivPDw-%7;2$ckqWKP20F36Tyu5 z#s^CidM<^mjY%tmypHfRl<3SkL-S~7o+ln<`{2hL58g|#{P&}T{Pn)h%xT=x<06Nhc;F!YQ%TX&D9FwDf=*woJ}vQ)z-zK^iDqo0?-} zPIr;x(?__uOzgs&V4a@d-Amvvr~tUJs5ApZbH5}((VWyBMrum_vG4dr` zZiC9&o`r73AuqZlY|q6U+rY11!_9O$%fBRsozK2!dj^hq>RBA!pT5FRB4AZ~>o9{w zFqulNg~#Sd?&%9*a(wzm9!UVHnZ0tz|Bg>M46ebJ!Qo3dikk(o13y0>T2fYBCkyDm|NpHes$-3_bU5!%<|9mKlIuLix!FlcYkh=?aZwiIW9y>}WW(f1 zZxi)9^oMy%{hA)mNf$bj3WnPEk|1X|rFdW%Y1Ie1Rf2?8Qydr}FS>g`_EfXQk}5qO zRioCCiqF$kJ%W3gqO|a_;NydY2wD@u+Vlv$Mey7fHR|g{FA|aMZOVsWKcC^gLIA1^ z5|R35U*0{D@s`BDy~raUEoOdx&obNUUT$Z!{~_OnCANtf%;a*xTYy9_t&B>0hhWd# z*gZVMM^!9*cnTnS8_4R|m5g%xbHs!$7T;qBdn$e5 z+{rae=i} z(b-%;$%!yToVntB6YiYcI2D`|I>n3Or#Q09tj#ldj zs*(tCA~2RxJ>fL-q3F1g!~u)gfX!MBk0`KYBq4^xU87n!JEljzYq+}sjvCY~pU!&JNoy;HY;xx6OiV4I+}^G@NwGJk2=Ec%1~&^tjw1T#jvZ1n%R_ z35jlv-zc`pI98D2znZ^}Ju9VLjpO}G4dwwhEKIKSA`5Ha>2b{bK?ny++hq$+gqi zpLW;q(2yIjZ!YV&!MnRXow+E> z|9hnS=gdpr^&vgfKC+_BThY~fAFPcwZ`!y2F5^7kCjyY3T5v9_Hg>A+^eZ>|tT68m zT4{Brekht!!#g$32~qwR*Zy;lp8v;A-U`AF(lHq??<-kH)SjrT;li;N0h$eo%Ecm_ zfuk+7&d9;j+=7ud?TeU~lq(RrpC=i)AiB2S${y`nTA5SbIsGqT)6BYBKsx7!)^G0I zhQ|y4fif0)k{MY0jIV7XX^m>T73rEwY90#W)@}-G7bi{ z>)Vjp@KmQcE6GcT>p)HmbMj&Shzqay$3LrFo3rX(Un@m5Q_KdCx!F*Vma_(+1BUe- z|5+j|PoK|)D9P(b1{4$OzO~(03)D(@ACoZSgf~-R{6xT%&X$ON>)P7s_n_CU*w+H^ zrJT}-p3)sydP74D&D7`M;9%}+qBbELZ~Q|B6$N$mzN7(|DxI?ZlYWY(XUeMZMw9j6 z7t52=vgRd){9luclq1v(i4N~8CMRW+<*gjmp&u$KWw)cX)@X!F->V z{Bpew94?0)K>3C}p2Mg6K$bAR{Q}8a`YkaKU0dbr+PyTY=KFvpdzFN7Uz-&q42y%Z zsXIAfB1u}kA~SM=7Qbk1Je&3vWwC<9!sf@Rn(Z$Kn=cWV^m(35^drvl^mnbUr`KTq ze>^?<6-|51E~xJpN6XR0FAqf>#YpFTZ&;k>c$4iv`==D0jvl?xCgDA^4)xvfl~Fmy z?yQfGb|RcSk#yEpch?5+Qx?9^X`#*)((re|%*Gy6&tzv7YfQPu;>g>y+dJD-d&P3G z-wyP)U?bY%+q)p|H&$9~&wYXPp`KZvIn>w%CsdMEAvUJs;{HUzlUSU9kaX{o(0?t2 z`#C?H|5l)|^Dj`#{cVsVz}E((yfO88Q>Mic@Pjr~90PF%5q7SRM`s?tK`OAbUH21Q zZhnXjjMuVS1(y!U{3hg(hAluc6Xr9!1HW9K@}a*uH~R~>AfT!AWh`!xG_O)}yWgR} zz5LSR2F`X38fdk+Z%xb5u64BSo=+nXPG-5g9{JfVrVLRx%V?4mWVHz8&YhHd<$Mt{ zPS#fyWD7qjY&p_J#LzVnmxF?&Z73R^J~Iqffhn5dAH;J@=SW$Yu~ad$PQ zG*mvcuPKP^FtbWJ*y?0)6a64>6UlaqaMquOLSI%(+ajQDUo{R-_dRW5#(q|NSy8s| zlPH|*Xy++7Sl^pEE-yIHBe%XI9f-Ln^_XJ;N8|i{J0b!{5)5wj=sCk3$LRkN5G3mP z`py0Mm4>-GD&?rIjj+*nV~NYd;Bx9S&+Eg|QY!#bajt!evGna3yrMLQ%R)oMfknOP z>?f$3=Cx>1aLH})Laj`N$%bqr8{2tdy!Asm5}{&xk<$P$EmME|>!6LUQmb{Q5;9WY z>)JcnhDp~gjD%z*E!kNb1;yoZiM^O&or0*96i~vLv7-EPkL?cUF-tuo)SRuS;~Q=9 zMK@3>a5>Or`q~0gn5&ca)a+xkJ&HW;PXr(NJ0Q@cm}Y^=>HO?&4Gm3EMQzMY0P}iWUPz4>m<4yw(d-3PCApcHw3w8nRu~&X zeM+zBdz==li_@aynMsAL97>2Pyf!6a8kH$?`1=~qy}sCN(boCq8g&uFzc{3NhVkKM z;eQ)!|KUMsFTNb0N18n(#AETt1P5yYkOk}zw~xZ_cworTgn94qSls0x6UGa! z2qCLZi}v_@{Owvp!R}QCEMW9 z)9UzO8YikWfcQr5XeMe;|Axx*8|DmuL09?P?*;%+3z3XMU?2M0keStXcy(~5SxK|o zOxe@G&g#$hmPk16WhndO^$MJg1^stEVJoeBtbwrG?j$c}SD&%5E23tel~Sa*&O#Pl z*r0e~483RIDwgr46m1PJ=($hMcJ$A?#b%BD+9=jCHz0SqZ)qZY*sg+1c;KYVA#)UZ zli8~GlgwUq`T1Ka$97QBA8bUTw`+GYq|up@jU-A8#;TncR_9Bupw!NBCX8Jpt|Qzs zu)8;EaSwP30UKcitOWDQs1%*84KuN~^-NsSCB8d90-53eF~o}Kxy%Dktf-r(m%7ib zFwrF`nyku4O3P@A8xOvuFwBQZqY|=OsL}GrhI_T?Jc8K?`-5(b9Ac^!^pu7mPQ+%X zSMG+S!+Cz-TNF)7Go)*N9#hJq#D@6Ll6tfm(q(U=nR}FeCX9_K`i!7>d6ER9ss_nK z-qZNLzHz_33jd#_&R3Wpg1o<9luj!Go6lGIjpj%0X}!%FZp@lIc0CsCq<#^ZpoR@o zh3_SNW+sj2ur`@p8MjXGxm>U&1&)))tC83E98)VTkjB>=;Y(hUQxn_mh8xGLhrg7w z*IBsy{f!c4#a?rFk8Zu(EE@-0ZL}^li?KCQJS?mq#`0ZWybvxsWCehYp-&D6?MX|Mo&8i@>`?yw9Uu6={ zxadZu2`;2(reD1toAe@#ba78($VQ$)Kud~wav9&V_+bPIRB7c@ajtD-whE&z?#8>u zvvYXvS89REMHKdf2`Blwfpw>l9k6bo9uK>b)@Vv{8j^CY8}wx*Ak9GJ#Hg! ztiRPg&FsUiGwcQ%F+|xqQu?>8y=@!U#N*_69Tq9ZpcR@|9Cs0t4dVU%Jba2W6XR<0 zZoWw$`{^J565DO=PJCqW>z|B~khgf%KJ4Rcxq3IX0<*G92gar};UEM&sx~o?b0{BV zbf1xqp{wI^dy7*!gT<gB#j^G+j)9n?XF#`xh5_XcvM; zfnO!Qp%{U=FD{xr+johMvA()7P>$%@>AKOu`fTzSbMx_myl&;>Ctu~<1p05^vYk#h zoF4SFC%CNMHHB;koQa7k>{}%UOJR7#t;RFT-5eTwM@k)8D9S6)tXesBNj|EauGU*% zmbEY6*C~z#SpBE2@cc>ozJG%!C#FpcEMc9lN(^!21&}iwh~$RN-pl#47i{G{P@}*_Of&8Ogw-y4+F-l8)RQ@ROnlDR1M{IEnR5_~p&7VDxX) zO`KYbQ*o9a)l=zS`+NN0#_))moGLfijKJ(q@}Aw9YYUynGI5ak5|? zb^z>mP@R|FjlsvyDD|%tp=KtEDyVSl`GvW^y7Y~{P8MV>K`t1=#>93@KYd{kv5Bk$ zKi{2mXpkrT6FM0Fnf(f1s4ifLi-0BA^*PH?uH*B22Nr8Lq};&^o4Grr2a4BtvMr7z zc=z&<%+t|5`mV<*P=G}2iOIPH6AGqzw4Z+ON{gd3tzM@~lbYE46trNT z8A5@}U$w~&BCtUy*t8GQ8eigwrgt{NNm$4N*2ZWZE<-&9NP<`$x(=g9NZrmT9myk2 z?)FL}vlxRE0pu)_H&f}Ze5ge_lZjLuOn?)*HO^f%+YSo?xPu9^p7v*2&H7Ye)0oM% zKTq>(w5X9SrqgA7n`W#1_tyu40>vc;&*-_U`;Q2;1r7yOtDK_7EErW(0m2fq$q%D& zYSuZ*NXo)D_h3YvG`d8!`CKNesUx~0*K#@Zbxt3cE#k}Rd^x4n2s9YDnA2nQRh_LWn7Cqv zM&(=IrpvsDX9CDd4Jyi&ja{39GrhEwpDqzA|BQIu#C9N$7HmB`V{KVnAx46#ET#Kh zcM%-WUW-;<1(IuntD6Wv!YD`OuC_QXD<8;FnznC12$&9+9y*)jm|3YR&^^rgTlK}J z7%r(0LA4S~I0DNqLaMV!&92wPyf@dbXk$qZ*NFOres)9WkCb9Sr)Z?4vV?XAR!kXm z(39?sN}HCVM0q)KzG#@}df>!%p6KeI@Xm`QZ=?QyAAk+!Umd^_5x`5WqBKl;U zgy~KWJV4+CV{pS9rep95E}HL!KAq>j#ZTzFPxs)95O+ zYr~=(pU%nkyr0pPl;e$OB!B3hKFGa#xBOF#O{4t+79}N(VoRkcO;U!!u)bK6wyQ42)whoj98oa@^J1h)py4smp1-d?W z;4RfeAj!DC>)+6|+ocF9Cz zYkfL<{X%S1O~U3Kj5SHAgi4Nr9WQ8l;!fO)A{m-;^AbhQ;fCULKySFM8#9|@yX(~w z%{fmj=B(mUp8pGBfdrhmzIxYP}GqlR?Q*Yki`}5>7dpS9axyDG)5iG&3k% zrGJyiIhS*M;Wz*KXen6y)VX@hatlhl!8Jz%pF0Q3^v5LQ}8v)8jl025#_l zT*v%x%|+ijxbOh^=TA{y;`n7vq&;pt^|qNVt*r&{uglggLjyu1SuzR zaNr$p@N01BCJLnTbXk9h7nDO|vun_jpbvI`NLuC6SSI(eitAd{w=~lai-I!QY5$S( z*0I;`);vNUEf*c$6{FfP-0~==5^=4zx}V`^7M-fmOzKYt7og!Wi*?cALj6b^X7Wt( z9V{9}L_&5y`Kr8zgne9KdJvnKB`qQY!!P*V{aGrsZ)-I=waqI8VqFYIOh!5GS2hvUPX3Zy<7FZTzV@hH1uftde8wj8p+>5Z+nhSr1 z4Lt(p9{P2-3#C^mUaYA_-G{x?eRhrDba*P8SP@<~&)0Vx*VA2eDGhsgrrg><4_H)W zJTg?^umctIHd&m$#ZFe71n+P@o#a_*#TXiBY7{$x=HmT&FA8_Eq@777l{4vDnS#aQ zMul8Hb;1R;>M(eigT-xt_h8eR!fowuD0CCUUgPRP-O&S&vCw5zP(<^;3zIeAA^zLb zEfVWDZNOx$7XP|aazsOe${cn{m0gbH65i%zxyhy)#(-HBnd)Jb(N5~op zv=~5ew{iuU zlnEP#E`DVZc?JfQt8{vXxFAHa%joiiH^Y^Os$JNIxo|SbDGtc#8pxoXT|v`n&PUET zD;ex6F7p~}KeWzGK_yeCi6xci^=?@Ecs_JmbmSf8;#9^Ct_IV|0N2zb1+^Tj)5JqX z;swhw-Fl9U-VM_aUB^8;Kf!fM&j~Jk43#odR&Jtze%g>lsn{2%G}d~p2FIuJ&K5bu zxTN;8yO&M7+s&St^I-~P4~!0!sJvtve0os5(^6&gnGr%i5apNx_-SErab`+^qPk(? z*F%8jiN0urXr%7qA34RS@e1TyfFRAmrNG@{fG_v|)%92`VHK4?g_8K8M3gqONWl3? z=GocQMkGbH@6$k{1h>MSke){Y9Hw<;aM?{9Uy8W8Gy3#u_ zMU8)yrd(1x>bo!1`ooAV>Z7*DGGra~{2@b@dY#P1wo#tH42q<=-E z8nZK#$wKbLM9ERme$xGvc6VoHVsa1(9EkgwAgbg1L(s1?5<7t^!A)sio{Bkd@)Ol& zDsHI-_PU<0Bvr2lCQSQpEsv&0eJwFo>6Ed92d-V=o#&9xMiXLONv`#Nyh6K2NTso_*sG(Il%~i^-v#rvih*b?Jn@SRh-WAWio|A1F9~H865b86))Wz;Ku$>&+-N>FHkKzNv!a%4 zVWCoO7)3XeUuZVIY`>LNZ=NzZbneI;g}H7*8(5hd0OG%ClQQj>Wqu|R|CyaO zbW{t>i&3amt0g5j4t0nj(i(E4)$dy_VnEvy@ zcO>m5Sstw4QgY=Nhc<*#&n9BKucVD+P0<}w5&LzTD+F7 z3=$4kdsuAY)L17*wR)9SZ3c>O6J+*G#d7v4)qRr;C1E6w>^}NM3=j&7L`>+b=*!#P z??rSt&i@uBzYjt9IsMh^kE13Dk?jliP4Osf??}k+Df%w)sz#irJmVC&R{8`pz&uCdZOI^$bI z0Tt{X){!yL{rQ49Y;jYzjF{&Sf1g+X3p6vBM}(XyTuO3>ZIBc8(&4|EK`UfPW4@&1=FSi7j;(S{H=UB39!LEug5=ssWm@?x@MJs5cp zQ&__ukH`mE1X?_T4gFDFqd;cm(AXFS7hBNS{M)tSwn*^Tcr;u&HIFY`ASz?CLS_${ zXm^6WkyKU-6jX|cT`-djHizFapqR9hLR8VwNjegAQdo6^BfQa(K$&SsQX6}79$o7mw02uQPgP`TNS!L%^{tE5F{ z4Ogd&*kpt9xZ9(ASgOVjr!5m8RGD8Y8KPxlwj4jG(R%b9W5P4A(2ckMe%2PS5{Nq_ zF+xN{9|wO;DArNhb!qq$A0a}cM?^AZ{Ymb2+yr6pHPI@$vj zPEUn$u4P4GN56l6UYy}6bDrA?BM1A8S}}OPKL5Brr^)K*FE%5q<-Wa&cElHPX_j+( z3SA=^_I&h+N{saRKf~L1fVXlaE{9CUBj=hSg1s*(aLv72{jcgto(Qm}lZ zTEreu5*_@VgnrAHCTnlI+wa12@#v+FQaaaT|Z);*%s0Dl`*{1PtIe-JzNTql$apm0-y~a=MUqs zg$3R*krqYnI<}6!D!JfWwsTpbFV(hUHfEq(n^U^_SA$KiC5J+@^QnyJbD)V zy3xx(A1zYb1eH(x9a72os3K%Uy-ThqF3~KaqB9x9j0rnBc1E}0Sg@5Yc( z@@fnbND5gtKKam+yb)g`$QwWSw{fnQ?3y?1GZ=4tD6M7>^Crlwy-V$#BYR6O>C-R# zjuiL5TiwP9iOip;Z=nnkIlwP>b@rrGOD`=6#>~>~?`;79jUCwCHq*w|ZwKQNvWOEF zmHN%X#u9if3lAksU6b+t;^QF4H2Hq*YZt=0z^4WTsxw|>3BnT|4=T732E#uVZT@0- zLA*=sGl%*@e6%S)lDio5`5k7q>G6|C6qcAkHAKknjoouFFFq5%-{STtWE*}FzPfQW z0}nwGz=&ph5^itr?_n|0MD*mD{2jsnV4169oX_~~7>xBU`Js+CeVgBa2Kq?t>jBqz z2Qh;Rghsu)tzq|poX;(!`-2hi2*j-2DNCUWJH0{@p@?KGRKbyf8cL`}VDB^$IWg)M zE^L`J&gAc?%pg|&6bry0llPs9X;haU`Rzrs1(oyxU-$T}t;q&{lhf<@ZOi#Wx@Noi z=g|wjAse{EtJ_?GT(p<{X*f&%mu*tavhsb#)sr;t<*#k|YVycJJd#?ssm=K)hLR<*)8!=@4oCrbyMHaN!Au?C$6 zEt8wcxwSx15}-$EP^77j4LQ#I{7!~PJv|8>H>`Tv_|Z8vS~5<(ESou69$yN2L{F&b z9e_1?W=^JT(JeG9$W-V=F zJ6=Zd3D~C{h>L>Oj}O{s>=(O!c{EaTIaDbTvrpND>Oa@ot%Jg?>i@+oko^ z?&HUhatyzu-Ua2dd9q`(WVl{h#w4UN6e93v74Sv?!2U^Fyn6heBFAnpi1!BESE1GA z-_*!Ea*CUEcrHuh4jd;L%erQLUk~1$Uk!+}?fdq4MKQ+m#{fw{$otKNnL+$PCb8Fg zR#H|j?p8xm)r@7vNkS6iy`O9}R2uD+BKBtrRWz`7NsfY_KDZQhfYGu0ckm<5*ia8a zB-V}~VN)k*gi{@hD6TL0Eh#fOAC>S#TuLU^$U7YQ_0vvRyYnI%K^s%Rq3!5yWq;H4 z%Q_tJIM;Kj>(I<+!!3glaj(u(|Fc=ROd@V;^OSi}&9YchX%q|(T6xCKYdK!x%>lX= zqvw8ejcV-fsTEOY#t%pD+5m$$X-BjIpRvXEh!+S()#^`7V{Jr8|P=F zod&BW5cL~k1Q|b7LiZGB-p))|SWA|F8ja)UaFQhUA4%#<-Z_cNWFB(rsm&UmK~O0& z8KoA0e`Iu`viNJQS4c+d#VEL0E4n4ZH{p@Pq}#VIXyO zf&%8nd?*(kl@|M_gE0`3HJ6>_M*T*`V4%%r2Wfs}mlzv?TP45%cbTt5ak)=lp?@Z% z3TaqVFYlTn<0V9>mn5>-;Ykw$gJz>(qSZ7_nB~iwY2tvMQZDPpdP%8u%!Ao{pU!U- zf7B-RTKNX4ls;<6!VQ+MeqG^GoPS7R)TT1q3PPcg=YRM-J7`k7S7dzA#g-sInw8_5cR<_x*vV|5&#v7Hd$lX$7fHtExXw%j6LP{&D#^9pecRsBHQU&vY+ik$zXRe z4+qM4#?E{*&K>c#Uwkd$`wqeA#CU8N-7^;mOIk&P(a^6G90rh*A-&!vD(DwUz{3_a zGB0`KA|Z;ds5idG8;4-+@yMel0V_-2bvR6M>INov4lJBB?Qe-O7@9+X5Smdm&!N+5 zdpgMJ)*6GZRhIlVdBYnvW%R~khSllDKNzWtN6tsJLFZF`Ss6_JIQRl0`xg3Ks!@m| zmPvEv@G1+IE$*5wc#w#K|0MkLOz0^<|Bmq=?(PuLf_ zZ&=4Wozju=KTlJCd0LIaxHww=znh(|>@l9_rUamA;g?L!h?zX$Vs(dpBXC}c=<3>^ z_2ZoU**}UIv&Uy5RtkB_Dc!0phzZ|=o~eHXeE~SJ(H)RS!mzDCp6 zA*MhV%gO@)WMcVG8y4VFmAoYCHXPZd1{|Eq@%qr((5BC(rKtghVnZw8vVg+=<=>tu zv9spjoQA1o%h>NcDY6lLCCPm7m1;B?m3eJS6{0b6s&oh4et%1o%hkC}gvKi>U{YWT zCEqqG1TQP{q`iZfy`k%ygl{FoZ4BoBy&E>tVMOV8_1dBW+*TCX=0^i@lVR>mC@8I& zbKG3=W*}*Vinw83s+cU10}vSJT`%1ip)!?Y7)t);Bfmees4CG4Uyf<;UL(`!<4$WC zPM+9a$PX~xNC>6>q{Yam>NKrUtl=N^qVMw?9{*ura>Em%)_~1SV zmhZ_-#6yhP;&@$;EuNXp=gl2-_8l%FwtTs26XGXIZ>%-BMQpTP8D6;mV&zurJ^sq< zTH%weYb9X3+Sc~uzKiKq|KP;l*_vQu=hgkdAz*ylc3Ept$XWFkSXnLr7)_Ih<~N*e zMOtcBduuest?sDcbrwq0=r6&oGfwokq1d-oXM*?;O+ zag4R{N6pou$jg2B}c8{JM?QOZ5MUmfgP?WQ=0)oKHZ<`mjQy~t*=v~W*aN0P#Av^ajTT3&5Hld zi$_c=;t`01VVumS1JJN&Yn|&$qJF<{M&i{fY5AobJ>f;jrjZ^v@UIlskWu)NDm!aG zK~p6PSa2eoxSwS3mD^aA0>Oj(I%tQq9BO#0ZCZ|dA}I-VMdfYxab{9Zybe$zIOwd< zT#st3mI6}aY2TB}YMeUs=Fzig=39 z`=cZPLM$%p@_Ksdmg5q>Y_z?$v3c$pK_d`Rht0~6G-Mm%^#^L>C4O4Is`cVZ3O(Dl_g*4x=CV=*p)r*HGa2Df~U ztFXKN)8PdC`?^81QqTo87p0co$p39;`VfX7ANSW27?Y25{{FpaH>swe9Y7*W;oR+ zHZ>jNR`vw*)CjJB*(YPo8zHm z&Qn}riZ8P>$=bFDFU=IYH_0SFFq>BI*Ntl^gR)j3*m78%FZ3n}*!*U3;s2ozi|Y#5 zMqI&DWK!?KIJ8Omq+pdNz17jlx^XKxpk*nwsgQyD`SWV`t@vyDQ4-)#`dci1=&A$h z=axf>rNoGOG?AxUwcL?g_y@&}#%Mm(M9Nok=fC!-5c_~>i>%k>;FMobgYoc=)yJ-C@{4cI9#NShru1OByau8K% zeDWU!6K~#n>GI&HkNzFhpK;QpoGhs$X?nj!lSU@-2dg5I+KlJPEy&{z7oEA7X{_Nt zf`B8DW5j$Ex|Fv?PFwTi@CB?%;c^(TE-zLRhm$5R%g=HX-67@LE@^-K*lH(qdu2Ts zciMd}c847UOdb`(R=O_XHwoK7D*&|p2?n*(jxtVHl^W|5IQ?W>Uggfbf@j$897v{F;_U2lj zP#A-VIKRTJWJ(!H^91Kn>UvU9Y_e4=ry?L|MzJog8hh zI!^@|58-g-V}QX}^1N%}Y)D^9iUiOzCpfa}l!zcEKnf;#t1V6kUKu#Da==uG}76Ep+;xA^w z4-(c;cswbow5Q3b%s$buk(3aMIKksaG5FDE($|M$N*M9iF7NvS!`yE8lcn6g_aD=i zNGIC74y{_tlUQhy{nBpcWof5P8EBu!945n^}P(Y3XF&NC!pa6J8fT@ZN7LLV8O z_KlTnX9PBmf{QaSE0`Rhs)8fL8+UC=#q9isUJ{f0fi<26AmCbK&TMa8A7{9&G5t7i zY&Y$@r`Ps`tfE?z&1El)wzF@`t7{9&%LCz_y#?3(vc@nL)Kbc6+SSNQ1zye?eK$T! z{(V2hrM8||rg*UM3JIJWKH+hz%h+k8olO1XQd1W^hXqT`P;Pwv+nm4cNtjTlEo(TH zzhA#qXo&1lfGo+&dWVNtn6qi{g_6?Z|Ka!zNp8uJxC)gOqgIHMEVw6cK*S_@mulBr z9;V^HVlOAgyudtHhihA}W&L?LP*F-73+x175vHv;gZgCz7OdtKs$`6> zbWdn(TzH!&Y$a)u~qwMu@tE zgtjntWcZh;Q>(xh!lc%~N`_f!+UE87N+bSgN$aIHKqi5Q~KGS5`Jw%N8_^GR)G1AQ^^ANoD$2)n{}_HW}_FAx*xwqcP|r}Ws&90Ct(SN z7zPz46QVEzP#-yA#IBu@N$o~Sd8TH7CaG0g#9xG- zF=W`BL}fY}j?Ht%ty`_M);Q@9Ag?`UvB_}e&~!eo0L^oN#VKf4^Ba}ve+wGw@kMWO zP3}x*9znFpl2khRPC649Mh?SyG0$<{L6GjyYHs<3hQr+IV$_Ugwc~7VK3?WyTjo=G?s1cKgwpyJ?7`&; zSN8DR>6s#>*$b|ay7HK|=m~B+nPi>pCtc~TquIXz=+ZPy&`YDgcP|Feq5xbAyUTyAry)EjiaJ*c+(+mP;-xzq?)hi&QZNjX1-z>-jXyN$Mp ziOj`%^8uZfYJ;hkR?hnKg^4py5585+3!}pm{WHDWFP%jN*k4zd{Q6t&bL;$WF-5+9 zO=oxD2S-TnnZbzaRG87B^OdK8F2Q$k!NKhLo)%`vgao28B})8kre5dSsag~VkU~1H zo4>k_x1*JgfY0~12D2H!!FUeSA;H<{BA(DAO7sz*Ug#q-Q|KK*e_l7#Aifk~1Wtnp zo#vSQA6O0Yv0!Nt9axrf8ZpXJ)SP6>FvC!B3N*qLDLXmXW9js0X`+dutZO+u4r#iM5CRLJm z$r@P3c{deW^*oHjH==R8#A%}R<^gd-Y4 zRPNOoIU&N%f)F&3*tv-%Zk^4(_Rz{K$55olCDm!Ckm(~kFQU*8Xk<(rF;^9KVUj?x z(BXLO95E3o=s2M(+%MfYPp_6qY_9Y$4q&r8X^ItwKhYcg+|E%Xwn~^_zd39^3lyJN z4FFJLY#SO%2=kO%b19_s(yIUKFmf(0+GDTX&;~Gz<(6=3;jw4mEGQ=mm(7O}<9ati zg=fh~I4CIYL65knJmzw0-lbu7@EY(VY!Z*AtZQgngwBx2aqrN?SwAF5C}Q{HMd2aU zZAO1#vG4jXBB&UjuBU$npy|PqaN<6>WVoHBlr@#y9B;S|ey%`NfJly9RE>c{H(|NE zHF%B(Iq7KHtaNdMt&_xT;@AfDCTrH|Hy_E-3^X84;j_x=UitnQlcLjg zL1N<}9Sx)7&e^_=Kev;?T3E;%peS(+12&Qt13lS_+rwb2+pvP$U#{=km!tGHlgGIs z+UL(l;P3_7RKD)z-t{Y?#dATYc7qv=vxqwlSKggmctiw=fPnso!i%mqA{A(G%q-`Q z2tLt3SH&qdG7&Brb5sI=0XtFaZgKcrC_LuDP)KyNZpi)pfhr~=fp;A4| zPogoj&fS*n-Pk$#+HKfP7MDx`8A{R)dK}HZUaLwHn||<7T}il2uGAb>`kJ6-#JdcY zyCK!4Wzg!%NgjBsNTG0$a!*_{sJ;ZpPZNs)7H#oGC4=t{5MDZ4krX{zeWlmP~8Y3@MLXly^z{N(u+n!-XAv;#OPTpC4r~EHjv#RZC>3r#ex)vD?nG zXO1^<|1xw5opMBH+QniDM8{qC{+4RhP@Er*si$_DygZ(mRP>}`-B^%f4 zGhwZh60^gLaIf(_hCtrPE(xsWHbkX7HaYDL@?fu!C1+*cstwyVz(l2+L`w zGxf(FZ>7$Sz?QQHLQruzuFcBt*=r9xFxalt8xwSDIGQZ2>YBv~;8bp=La0G@kFku$ zWuSLzw8w^L5}w5*DFsPFTA9_XYUgVTdRJ5Q-6!#s5N^Xw!@f+RN;i-y*FSnV*ZW@& z&92EPrmi7X#cr@|ZO=fGBCuCqmJoe6OVRy=n^5lsxi2RW-sv=E=@-)4E4-=arZM~l zTUwwW^a#&QkxXNvGK1eAm&9V&5YF?>BrlW*Yq7z|DHgDp#Nb$tUc@zOeyXsB40NGN zBX%a64CU=kp{Z2Tp4=tpUy6OL(e%^|5}Jj2lMP8W<2!uH0|qnSNm9x^hJ@?UhG!t4 zmHET5C!4^r)?#-RZ>8g!%>C>oqaX5?)-|y2$oY!;#cC@Mz$7%butaTrQY7LQV%B8%&8iBfzpILJ(LdrPj} zF;b4wBi^$U;aJ;dod0bnd$rRGjg8YH>ce)NRFc2P_H7j955HhVsuV4`RnaF=`ZuJI8 z9!PJv2n&Dt_Wcz+!`j{5?HPTSP`T65j*#Dz957Xl^!@^g{M&SZjIV$5-+!~qOL|M*7Uj?X6YiFbmo$F4%m~LhA>RaPX!J2{ zubc+OOC{W4qYPgnj&N}K+H|j?MFlrdx{wNNw$TKWl*ZwQ+h{45AaLi9!1+kvaB#A6;!;Rjb7O(ZiC4fy3oO1mlqL59HM={m|~0j0e5>tc(~7 zkgfSd$QZ0bu4bc00EMIiXZ@oXM-M*3{`8Cpq234lBZGhV4^ZRL^()bC4&R0ON`rX= z%KIss@aQK^!h2!@!~6Pwd3&F0-Pik1v4eMxgvS8VTYrk{k2td&=}q!5vli(=Si63u zrQDstUO~APWhvb-xZ;)HgT7zqitokX!?()^_S0NTwPxwUC1b6v8&`QCkyZ|HW4)@l zX&yh7lQvQ+>oQ`6dsb~qo~1Vx3YIKGXA;Y;gI)NX^@I(U92Mv z&u?Aih#+lv^gWe%iAz{lQ1ecrV)eewm8kH^lgB#$x*6=a;{agEOT)McBzmXFYcp9%<}s_s27ygCnpSGUF-6 zD}|saFGLp9pczujlCsG46H9Z`*>VNJX*AMp2+jkIxj!BSS~P2@Uq9A9p1R&~*!2qw zfN4Tq%uz>1;PY-G?FghBS$%;QI&ZtfRyHy_+{+IDe%L)LZDXL&hw)cykAPSinQKdK z5EmEK4#t@TQ!V{Pz@4)%blicOD%3*@rd$eDeR_?`O1|YQIV4Z*IOequel3`^(IkMc zvZS+qtA(3zbgvgMBt9|dk;b`(=E$-HWm;o-(P*-H6gOsO@@|{nW)2*4xkU@d z>On%v0JB-Lp9KI2yGBEA*?n|I%_%=&2VBrJvcWTPf^Z}yPQT_4xcTIMcV}@+Z_+B@xn~+#rK2RgSD2i zCum_xa40USqV;?nwf;uxIyPl}`z z{$HK*apVa2GKp)IW>Fh{!oX2*Fl3gc*^w4XCS?d@j$d<)%^-Z2$9>i^w<>LGPkH0T zvb5FV*0C`*%+Dd)*U-*+7iV1bONa|tW8VS21Vc-Xq@)y|wDxTq1KL_^HHlG#A*fd&7PcyLJ@JmTf!Ic z=K|4z4g-4y%zmI52m}8j^?b*__Z#N}rSF?qC^9MrB^f*G@Az;huk|2NQHYUqUO zOT!FyDzdDV=T9>Jwf!vLFM%6RKRm+)`9IInA05LH5h!RVWA8v}v#7=GBk`Aw%Iz!B zqhluHZ8HGES@13;i`SW04W3ZQ%3O)_Zq;d<^MhJVCQo*zL;6IPt|j1h4ToNbH`nK) zGt=B-Q&CwNBSqf(1}^j2;*lqPe5^-pEP^eSC&f@gIVB^vn`ZB-du;D8)#;(%eA1v| z+pPOHQCzaim0i%;w)d4BM_6nsV6#h+?eb4CziX|h;QAwEig~F$j3*7z3wu*aLANCD z{9>&tJ{0>O3Bch0XYQyStP!qt7_yi*ZaEIA&zVyFc$YTx3&aJlPA&^~Rl?eEUh63l zL3cef#JFuX@^Gi}_*A*lJl6A0MV&1@7A(nsSUJE%nDAe>;%&E=QEbbnanW@V;u6=dfKlEl}h?&Up z=L>^078dDIyPcmXwmFJ1QS!Irx>biV`Fkdy_ox}XNXQpn*gi~wiEmQAs*RdN8cZQG zIT~`}TmLGg-`N{p4UcP!V;hyJ;a0fXxOdq5$j7Pfi%62-)fLvX?p-M9D_bn!`QVk_ zp?JHo%~dflQ1sguM~n<{u%h1^z$p&~8ju{+MndT}hT{sxB0VfjAJCh;3zWml`$WB$ za4I<(`F`3ha@kBT82&Q#Xn1_s78CHrFSN4UeBt>97jm2w$;*!QP!FhKa(Jh#qcx1s zRt+m`7N@kFkk?VG4qM61k$?It;HrbK=R&I`1gR>Z`mWx@(F_mO$4n(&EQF4g^(osPbShqyUhNsf<8oY9`vr|m;|l`yL@KXgtIsX)?Nvz7*m%YFFB4S- zo>r&-ds@;I6Vu{$1U~SdE>#<^|4p%5?Fei>-7r4%!CMBprO55ruK`82>^bfIq9EC^ z=7$gJXMbBXDDOGDn^WX3?T&{cC+rN`Ll`PKKfj-9R3E$(@JYui#t-1J&31?a$p;x3 zNj^NxUnE5|EIf)=s-o=(ecp`I$9-iR@Zu zr}FY_UuOsZ!Zr!77&ZkGjOxpHcDh-ePL7(kHrU12<&rP>i+yOQmpi9X$T*z5N06qja3o}xRsdkjv0FPONi zYY^pLLSkBAk0Y}44mQ~Vhw!+IoEhvf*mQ8yYh3q@{0Ac^pkZ|U`3CbL+m5tne&{&L zW>oz3hvHJB%_8 z|2MMJp5>_snWQwRRDLG$36aGiPQ*WH+^e4IlYy!1?kv`YSYrlWG}df`eyoAh;jRU{ zjZ$NTWJB@NMo#?O5M&vuNJ?)E8%5}wAW&*sj(JMvb?^>Y84Ogxl7x62)tA86qZ%u+ z%A_~s07cqpXAS3=ISgdH0Jfw?hpmlFN37RJ-U~gaAm)BjDcMM@SGw~lA4dHLqvQt* zPc{CJK9;9%Vra;T{{|T0Z*(hrM#Gyw)%^;EzcDuofCR(e8(GyRn0$85P1$32nb!h^ z?@suFNeKO)LM4##ab&Dqxwq>ROnM~IFtB9RYv==RFEM0E<#bB+avJ8d+2;w5P3f~gI0zbh3>R~i4Y4e8THiwc zba3n;4*2?&LS!n8IB;6YkaWN|BJwH$1qEHi*UawG51Z~nvA%>gA}2w@LIbwlt8ipu zf{e+Q-LzpS+{YGwj#6%`qZ}=b#h!o8LLMWnKRF$(ZTrs(z-^VMb;5LJ)~CEmc{b0* z=|F`nH^4a&4l7xYzHImGyYp0b`*?cP0{&Y`{I1VUyHm@*jfaeY3jhWc9PabB7LL!< zLc^mgN7&?|(~Ta&qtF%pBco5EPEJY8v~@~DD072N9!2BFVUDlwtf+H!HEt?924Dgf z)IbkyMnFT}u;%R_2i}7>^XZLwyiYj{Z;Vbu}*;j}sBWohnx~dFXUqF*rFHM)7U5#Ux)+g0?$$x?q6G?RmxnZd!4Si_UE$>&e?NQr?`&{|ww}%O%!V0M zhn4a|!e;)U1+t^BDoLlq4aw64+wut=OGg&Ay|-KpFTH+@FUMqVTiBzCt)QqXoF0RA z*wnPz2A^wA$DHH#xeMB>3|-x7tqIocV1%k`$MlYnk(@okz1-qV23`t!t^) ztT=U6bom#^Nw34#z6r{cXpiq{fnv4Yzp~3wEKM;uE2AXr5waO3^qiNu8)&n?z#tVM zkD5d+#OmW_?xGUJ!ggoj%AZwQS}W~0@;b)Lm1*Gc9nH_13cU)Fy@p=bDCy|!69Lw* zzVIuTmx>>QW^`m1cFcem{&9$+G?^|x67ODM78kBjQgoo) z8^5NM;Fe+!jG}W5RaXt$Xcln&xdB^oH4rV!np(o$LsOI}mh5s~xyMF*XKp=Zwyxmj z8jkwnk(~#&*uTMpI!xR2bnIDRy(aO@491x`olE-01$yh@a`S_MI zFD%9t%m-eRjCtNG_ZU~(%wWf1_QtZ~=5b-#>X-vmTT31^3^;;bE!G9Pkm!B?5 zgiM2?<>@#Zp4VgSv{w)!Mtt@|uy9hjGG+>I%%mbSlO1I$8eV)@-^q+!4H#*p`>`=S zkG5a6yDsDj{dT_m5qhIeDxEaHS^jQDDQ9{R{GGqn#WEf1y=hB0GfCfo6cQr;AOZn|UzFN!Y zHyVEbG0z-BU#ME4rnLK7p#eT70dS;d?(PIu&R#ZF?m^HL((S}Xl$v$zNRCZUq8Dlc z#0Hy^!I(ZxSLIlmR}<9_O|3!fbBsarJ%g`(ja*%^S+%G`B>#o>dFL`}w6fuGZCirs z`9whhotnp`<9FGBRpg1OWmNN!v9-I2AiJE=@ESJt;=Or;|v~ zu2k$4#WWKk)8;o!p)1xOaO!Vr)1d3W?%h3kJHP64gtBY)wb}yJeG_>lNh(IUI96w1~?qKjmiVpHBEVWZF^nqbJtr}xd zgU~V8`VuNMV%3`xIgM$`wOb*c!!O_!wr~XkGR?jiDH%#yo``?LseccIB#?K<$>uP8 zOqxHu`8*#fQgN$pLl{Cl$a42EWP!UPQsUA*nbvbwut!0Cl&>)>dC}VF z(Ox=z8cQl(se?LK-haB%`M{AJ@!wgHrH)x67ZH&-V?9wnza3P3AS9C?EOW#vZ=zAORSs z)B>}&EBxb`>`g{0P0Ff%k)Z2qLTRf!qHU6orfjC)h*x5`|&j@zGx%hauu_CKuW!rj=p3OA8m z=+vOqHK%aPgJBjL5jjZcmsni<4L^B9VYz{o80@4UCrVs2R>*I)5nV4rIsXf4*v3TM z&K#me`NKt&oetw&X*{lM`@_y(9tqI$46&6KR*a<`4|o|LccgQaF9~~?;JV&xK*RC} z62Y%^rI3v;)k|4vnH=-hbe=*}`iKKvCY2)RR);ndmU@?16a8Hr^HoG+dC95V#VrL^ zP9nMlR5=(-OVRe|$8x^zrp&@)g3wVhY`PW@1D-5E0Uei7WDwc}=%THy6+N*qbkQy< z^)z76Bmu|k^IZedpKU>xU2V_4K(MjF{E$|^)?4u-bSGs@K%Te|{rMNx)_!dM^h7$#D7a8rLz zv8{*eR}X9HM-1r%9dC7cJ_+^mq{Q<2k(EX9+itV`|xe1!gL{=LX@Sid@Dd>4qdJ)lh+as zsSPhYuI{nWX2*JEqq&aOm4+A4 z<02iAIofuH=ed3D;rX8Kq5b#*35$6{C;;wW9SMn0-mSeNP*HJ6PKqv`$2`(SJYItN z!AA-T3MpNKJG)|^Ga}C^$aLt2G@ys6_6G>HUKH63-f0y3DihzGw0GgamYocuZ^x}f zub_<~W1`B=EVXdHTw~$y^8CuQ#+rS2pg%SC$Y?g$7g&4^^RHdZ#Z1I5KOAl%;+pzcYyRdM9_d228)nY>yY2}j2q+qbRk6+ zNW+Da<4XV|ZTb^2oRXhCJx?j33Rm9DlUCb0DLi(BlAkp7N3Iq)r_t?0B)pF?D9!2tO&RRc3Tp_6tRp);4CcUSNE-Y+vCM?|GkyCmo6^cZp z;H1QjbKHK11(3l$=h)#02koSU%nU>=OhQ}pmA9w?h~_WHm&{GgA@X@Qao8`-X>GWFbV@jysp z`dKc+v-faTY=MZ+xQ7%69G~SQGV7}zYqO2;lvuw%GK4=gg!wRp5rFwGnEHhIkIlbF z8nVKI+<_xN&Qb-4)viIT(zf4*e+(~SAg!ShzH33swlM@TEMiBL4u`>j_K~m#v~njH zhlJPvhNgL3Rgw1{BgT9p4c!~j_v$Ah)WAx$k`ea@rhk{^t--N&U8XV(-qT$l3Viy* z_wx>&jUET?_rEO{Ok6J0ZpHvN@wB-n=(B3rUHa**?W~ zb1_VhcK{?b01hEW4FZ_$PxBgH*d5pBqw3l-owQb2(s%Y zRDS#+?FKR?*HIxFH&I)w=!x4_^yXKHJ6atC(F{oEv_d6SB&vkr4D8poGf*cSDj0z7 z2I%17J0fyv*S$bj>qcTw=DLT?sP_wXlhUtm9@XHAD{Tfm*CgygkTit-v%Gd! zs74@^SD{`^jX~d(R}hTn>py?!Oc+m3oVYQp?0B0vXp!xSJb92e&zh5Uge&cfCZgO8pF*1RmG8fg*J=L6A6wi;1?LXlYswF^b@l%X74RKkPj6nW)V*+g2~AQ!lL16ia4W+ zqS+JK<{)AZ)bhtAvmEr2Q z470+j{U#%e@&F(Tmx_0;XVWyY-HKI_edB?JSEX0RraHYQ;xAe$$L~ksn)Nk5*59Kh z{Ze5bIf*4``RSTmGLB-6E%2$%*{pb+n9(1;uRdMv_#D4d%?Ui+Pg5MD%8U0JQsXJH zAQMQauqaiOA1~hIbybivhLH_Xtq(9cP@>SxT|dN-keSm9=CBmxMu zw_THiWFBhpllBhOQyPdRyVv_>&W%8pVNGj z0D+D3omnDoyuW{!*dZdmJDqmjQKcMvo z@HffGc6f+Hkcfzg2?*rBx`jw3cr|Kf&jdZm$$t2_CLMHzu>zNnpL5_IU`RMcSgCi- z3Pv^cP6YtmeIJ6X30N3=ieI;3}n@21)gc2{g~)$<|}lpj&vGGc<;)U*Z_18DcI`a~G@ zX?InGVZMjB?HxvO2x|3R?{d5W>ax&EZAN;O#>!1oy>_+_wcHQ===JJ??~?Ua%Kj{# zYYw!(3c-C$#9xry{$Igg*M9_mn-Hlw>E$Kq?HMMAjy#(}6iSqOl(t7=Y1jIQt_O6I zx@2)d1RT*?KTwUtb!aJTZl%5CDZ>&fvF%w3%G(k{sOR>}j||)1lLG%K)}0@gH!?AV z`%H?cR0d{bm_U*Ig72{#iWarVgimr|Lpq?x#uv1@3sN=xt$w=QE8Kfb@pFXb=u+;6 zJBhWI!yD%qgz9eeu#zOl!=E@`p>Q(Z87GEl)x0Tc*e>hek8mI@*PIh1?(#PjMjtR4 zSuub?)jOMZRJ){$Z)n~zTi{(xUV6Fv^q zUvPPXJRUVnZ0IaEvvc4P-=TzB`9d@v5#R*YqX>G%v)N2raq%(>|)N^aAtB5yW1?M zHacDZa!0@!R6D6w(0X*_M5`Rd!|vLa=fzd4kTJ?o>8@JZs&Y(yU{|8FWAKV5GobGJ zK*@_2u)`?CHJd9$hHk``J)GNTY6bu3>x=3mi!f?=dxg`LN-OzArZR(0h=F|h6y>3E zoE<0Fz4SHRM*;-cJoc_>Dpy*<19jV#h*FQ2PL7jKdeCAq>F57d9xh);LScNkb~B`H ztH7}5?tQ@hIsN|)=>XmzOCZnG_&Ad|D+?c8Q#6{zgn8e46< z2%-2E?7Vz1bT_pp7S&Ie8yp}{sWG2>@mOwp(C4htCQ0&Au{v+TD9BFfTyDPc;|#Zz zJlq@2@lq+vRBKmfWu(}bzaf7WNdHKPPbNj5QF9(2A?6gw@!;y2aG^8UE1`%=cN+LQ ztKx_{^o9UQqB)pYTDqNObG({Wt-ZOZv~{{XrAUGYh_Ct&fEB=$Y{i{rzcl_Nb1C9N zBEzXryjY7yTfo+=#);^;B!_^gSSd^?az8YO)iZj9P4zMTe=#F*|L(`H zvby0F+fY&9@?k-CF{(BtVl$(Iyl9q{Zs;`nS(Pn-s`-)U3|o8}_Yto(M6ArK7<{TB z{+z1>X|tC@oFgybMY8U5*mLOO* z-#b;91fJXF06lT1egsc(c`{miX#X$Q!QVhAd%0pp)6~C3RizZu#pFC0ueZH|znkCo ziaLV5t`#tGxRnl!a>alcRy^wVsRBO(Mja3ARDUQszGb8?`A^~D2@Q~u2d6b@z5RX{ z?<4^Y$!zxti-|{*GP|OaNG~~;&5tq_yZh6&)VG5Awof>DYS*U*6=GqUFH=V~{DEbp zru`G&zKbPcV~V;ev2K4TgM!5qkkRB_&EQ#3tiPK6gu|A#oAd=14zv1z0fI04)IXw9 z-T*7aVGB8`dd7~$K~U<956N0j*NFxXU*9eY{?ty=tmxq}epJQK9@0+-_*q&lSA5I~Mrejq2?c&dI-j+7Xx2 zKax1YA3=OpW3sAiWOTXhi3CTw#*{D}u7$I`ea&i3<0UN-VmY$CIAhEsCINy0q2lAy zCV3@#uD<=2{KnjH>Es*gorIhXS_Vd#Mf!-+n(XeLN8~O^ zrH|YKh<<;LY=86W+}&lGd~_RLwdD5iCj18dgp7+#j7(0p9Pn*hSWqnTgMyWbT&XG| zo`r@{b4}N@&95(Ljpft$&-f=4BxMKm8xNDsW%gbUM=1R`sg&7o7Mn5_Z2r)6+V=iu zHJ#N0`WD0^dniP`E7Ba=HB9$p>`3F|PqTNHu9Duw=h6Ky+hNr6b{HxmA>%>+J}aXh zYL9*u#b?!TvK}?SgBBE(A`Q21+i%k_IOX{hZRSIF%qhe1phrPspBtIb+uH9;MP5mZ z*P2WM$F2Xv1xEdc3rzg~2kj(!F)-p~9N5&fHMKQiEMpAHjmewjJ=se!aY4fk@c*J# zeH7^Vt<#KY>Oyl68fA89QNKOrhkfFHI~ml9%vOf=KFAUD*5Gxs?r5!+Jfn2QTE2k- zd|p;<>+Ia+TuwbD@sW#e0zx}WKszf_F)Lh?hm#>l+gzk+ zwX!!5Dg*&hz?abe1;)NhN$DmA6G{t4Xj=cHIXd8m@;-X1s*W)6N+0vet z;S1LKmsJ->I8w1I%W>JgT^A*iUvvyQoWIC!dZAR#%2bv|P&vq$U*HiHE>t>|%PMJS zb0bw7>sfsDTU*CwHi3`pdE=2W#W`Q36#Ovak%sY5IsBINOd9iwgnWq8morLgrGgb#odbqcM8Rey99TNyStYHMS@#! ziW5Azdw`(D-6c519X9XGp4sz#KjOaEtaY8oarz&d8~R)dQ$6|1hDVyD&oeb|S^gV4 zh~69J(OuH}Yn=g2)6fpF>y%cyT6YxxznPyLtb_ruS&015bd@2GY>$(?BF>P8OQr&G zGzC}k3=>bS>k{2t3aIglRD;7p*Cz@)^Wh@TZ9(s)#x|A!oPp@qY~hTpofm?Ir%E5T zsF9)5X~C2+>tKA5K5D1aF8YIPX|B?ApyjGuw?1-N-}n|~3nD@z2@~q=L^=#F;Et1{O|YG zb)V@^Hc@JEStNNH0S+~Nx}8vYIu?!dqMiOPfL6x&Z|H84MU4O!}tRRSW0*)Q&l5xHqmF|s=m0=sA1qg!6* z4NG2#GhQ#z^&PF%?fOQo^DEvkzPhT&72h$ZBYiYHG$lR_x%wowst)l#pdkyZzea_1 z(9l|Qe49(Bj+!jQ>cVKttB~L-OQ@~w{)?l%&{&2ZM)g6jX(psq?0!U=PZvE<(CSC5 zM3ja$LwT)BL3K987}&X~Kz1zG^DH5Ti=ZO2qZ~0`=%bXx?OM7#*zEJEm;@~o=iaMB zZWIa-3d2)UDivt@ySM2Q9gIg3*hOdZ(HL@pB;OQ2IIm+OT)gp>=J)qlZK|ifRTNoD zW{$K!|FqM-fIi1Xl16QfnX^@&<|Vw-um~u(GE+|eO?|~0z+B^!_eP0fJ#3h#L$GS6 zxK_$gw>e||-`V?z;&{w#NqsBgpbid~a3`6A_kb~j{>M*7W|O}@EokNK%2Xu!&!7j; zHzJcw(c}0%ur^){FYsX3fa4SRz+GP=LPqgzQxqg5-gb9SgoN~Akt9mmT@q6D_G97k zg#HPE^zANpCFz}RwTqB#$V9}os=zQ3=zc_m2AgYMBR2;QHJ+{LFd1d>oXrri7-d^; zqe3fFAxG#C7LuhFVwu*-QO7g z`7CaZ(ed0a9o{aiKd(Uk*@Z;bXd( z<4nKys_A>g3-!I7B?f4Ry{UqKnING>;@#VSq&ODt9cUdt8=yeBT`!yRyFNxvnCu_? zz~aJ{u>BaHwm?J!K6ei7 z5YpNCm+65V_7^8(0SU}?ETyjS?_xrap;_C~;g(-E-fZ%|VD|LpA!8yWe-~lmWOnzE zoLF|-W4JslOKZCgn=)r#(91h`rxsp-Ywh6v%bsg4{jqq5A`bj&faSruh>KJ{cS_zd z{XTowl-CS~0d5i_pPtHiqezbNX)cIVNawq;F^8oRd7ju_tWlt5Z-)>HYbLLgX8Had zXk|XII*xjv^qYT6I0$jb=UtFJ2|~xtFXB4wZ*4xU^p#bPNXgOZBp#l$+!y*%u~rpg z*y8otjwmZ(L`uXEfosGsuW|OF6lGl1?7%=$UCl3k-+$k}!jQ-@Phw?NE=t?sXj{=;S)ON5 z@dxIRt2-4bRm!_zQ?xNp?e!3yt4>d8Q%`Iwk1D74$wyB>tAbc1D}SDLktgG|Kh#x2 zFI;jdT+CFgtbWSEa(_KK?es#S+l{Twv^hwGrw*~c@dAC zt-E%XR`n8dUF)UxjDmmU#ih_ki;165 zq>R$H?F+wpen`^dHlb%=nWx3ouSjLpYXFe#=Ry>GXzQik{q_;il@?H{C2W-qg}`a= z?Kex?iNUkK42#7W`d5E=OjJ&p+ReF0`lqtWlPvOcp`{o)Km^`H? z@3?vB?v+><=<9YWRrBCaGLJi_pmFB3Gvr6ox&!N?vl*=Mh@MA<*BChzpfc0l=Jo{0GVQgmYF zN_>cb(pn6zDozp>xW}K*%MM&dnN3b^?d0SB%1B9&Hp%=xqK<6>h{F^}DF^{_c26CT zf~jz7I_WNqs5$skMy7EW)R<|_ahr*z;4u^fO}C#<+P!&{SGgnT95cpS5L!^zUOK;< z72%F2XNphghPwk4k+&Y>d@-4j+@?hUj9nqwLVDB zm2Ris<9zrkDTNr$#trIV+14t#J(J*osNrvddETAY$-a+GlTz^@@7}UtzX~E~whJ=G zYVNZb0|;8<1FbLq#k@8N%;QSEkEJ#pc`N*KPlFhrjRy;py^Z~)Lq=E{%=FMQ1EJ(B0?cm zN#*r>>rM*^i!}8@=YZpQZ%2=|HC!=e8{BZjRy_XnFZ8+ATDUv^71^%A8Z*;)28;L@ zAn3TR(vg)~rw7M!`55+!v8PZGq{j`m&Cjdzeg4YL4Mbl-!x*Lg_66KjPJ*nI-m|wL ze`_{QbWOnRRINT7OOUY>x6%$)eDs?bxj~E^3ES^xs7ZAQR_p^V`dR`4+Jatv2b=kIh@0K0ry1Q?hOZ2C81QzQ^L()oU;Rg%&u-~ zB&Qp|GFx2S&+pCWjX4sJAEd(l6Na8V1^@T5wV5p$>++IU?EQVcL*Ti~pmA*=?}Mky z!!NxwVRP=oTL)!8NjWSl<5dnA>zx6gWX4S)F4gZ}!@7~#Nru8~iQdt8AGni@@?N`?L_!Nb zy$Id5^Z5RILGN@-yj(Z>kl=Y7`1^eG;)NlgYP3_zdBgd@hBYDZ8B_8@F@%{3b3EU* zfQ~MXl;Y+TNoYTfdZS9VZM(pY5A5QiN_uxk$1o_;ZH`Q!1av$5ED5IJJjI3O9d}B> z%_F99I#EelC8ERu7g16|WXG%uEmGz8K78EuE0xm4Nk{}}#}-1BDdF%>2s>0hrSe!M{BxN1$o7yEVu>fDFQ)+-5K{tO!u)J9}K~2eYJ|47KlP5 zEjcHx4ke1UCi2P(hG)OaXS{QjZ?zhh4U?3X%#UU@5KgUcJ5yqun9#F6nl`m&>C0=D z%PF}xZz`U7ijfx{+=dj{lTZ(}ne zg{z3~)`05vzs&#K`D#xw28ibrV#$!i6dp%H7KxqVyO_Wm<0S6_q$YWO~Ag}(-(B-S%Op4ALF_tn3& z?k#ta(lbwrL{*#eiei<2SK6;zUa54Do+0^gm3jzjV!Sr17^6DPh|z?0_VE*`YnYIV zeH5oAHh(vY0?oWvkw9df$-l~6j0~hFuR3w%B9A@z6XI$b3_B%LdTU_gZ+J~;-M$h z0md`i-kPOYww5UF)L5m*Rvk}f%Ufe#-!+70XGHsK*ek$<|dH%l@+?m zc_oLw7Zu2anDCoQjpFt7MUfaWV6IE%x;YHotSa5oxMt+ZRF6Ao!@fcgvXLI`R>#9BOXW1 z3`ugetgwuj3MzqTi)>tg{}kT`n#Aj&y5N?4USunFBPIn=nV`X)c2lJa$Y|WAHNm#T#Nx;J0%1Q#?3@)4wWDhuXIuPB%teFnsKW)vLh$;!3Imml#xZlon=R;mE4t%?h}sV>Wy zxNTci_VgfA0`zKpM8ql5oqwR0Xk>~x;iP^rL6~C3FpF~4HrPdoTGEK}42SR_V{}4Z z={jrDb^TX-@vI*#UJkXmlqHj80*f?3_K)RT%IsQM^yX;7Dx$tS1-ePkxANe&A-KGa zQj!gFWM_7ib0gP?K+OEMprAi>xIF1_Gl)@+QSTdYrXPYrAVOBPqaG9kq6H`!&7Kc0 zNL^=IZ)+!q`b!dLuiWBcRNbc5w~qfajgJt)b0cV*H!|5(w#@iOUrB_OGQ4MviX2HO zsXjvZHh8j?Y2%~haOf3HkNiDpPO7}cwYrJPMYvp=tU^DtgZ?A8NDgGTRZZiFY2w_} zxbbEs7E$jPs5#JBjCLe!odj=lR4TjMbi>KXD&KfWRP4b#$A6fP-DnTn68;-&=s@0t zfe{bq<;&DK3XJGW5%Sr2;3Z*rtar?z+{~oB+}~k!Bggo7eQu`W$i@fG&T*vYYc@6i z<@5ce!{ye2&AHMoTiuW58@tq47y)Uzj9mXWs!bRdr6Z$vVx{Fk*jkO{nvO@HXX=gc z!a%W6&W||?jDM@epBBz0VqZPJh7Rchv9B(u9!1`@$SR|_BRG@yj-*6rBCpgkuPoGT zw;ScA$?*95%@g=~Ya6>rCbIlKwrPm03b>y7sF9C`P=i4@f8tiVvM{R}8u9yyG zk!5L2y#51r7>7K($2!`P*Z%%9Ds`P*l?tcXcU6^K|C;`0?XLRv@ryiSdBC7?d3fdG zbaPdJ!1;7ifG7jpm2{S$D!k7RP;N@IP9$)CLc?&qSf*>*PZ?kkW;^=m?3j#){2;d? z=I!0iuEI7ougw~@{Wh}HrdeB8$=m*`d!+7XfDo~(CxX*=rWLGvZjuzaKS*Qm(x&il(6}KKLEr2ZS<{31 zq6IWeS_^)Wd?fFl3JxTDBp1DzyYIxc_xP0tyDCp1Q_Cl&<$x+}kco-$3%{Vk z9(iXD*Xf+)_{+C6OQ`l=>lyB8E$6~s%FnNCQIsr=9B4|iSR*zM@+P`_FuClwE;Yl7 z_v<>lEr*Uli2}ZY6rFCwW39TW{lr#H-BeMzsJjn!aF50L1>EH`Hk_)m-a4Z?orSPm zNu7s8DmX^7EQPg|xK%?oUr8}bD%!BPU{pJ{_rDpiC%f?;=I@VJyNI`cOCy09B-JR* zXkx;(l2jBV987pk5+dlec{QfKeH7@)_y!^4qQJdWZ4FUQxE0vjb z>~n3h9YS06lJue13vQTm)p0%)f?sB}W@Fc1YP&86iq|Z*Qmg8*t6yhl1V#oV>vEun zXgu)`d9ghD17ovb_Aw@btvtH!j zTnftSan_NGsDVL{vz@C#Ie-iH#*B=RPEeLu~5JD$@t$1{>M`-yOm46 zSC(<4MMFTR)#Vcj?5n_Rg*oEh{VmCJ&G{y(XN||qg^QP!$LsCU2XcS>8ccpsV00tN>-@d+?9ukJC36Zm zot&a^vTq>g#a1~SojF|4;W_Vq15Nsc`Ga30L@@5A_Xt1@xTE{yin|$d{f_n)$ znBOYLBDMMFBOyi5GV{kb(Qw3EGIOLj#L7ZePO2AhUmyE&mn|?!vZUaezExBe9uhYNS&1wJModrZ0NvfFZLcs z#DC+?5|Sfk&sl8Fd%qG;>y;8*PpDXTq^R<0x2sR*n`H7#vBRU_J9ZrjIjj&qeTxlk zh-Bp---ecGH4PS0h?8?cY4W=ri)&nBFTW=Ta{apxj?ZU=55rlH>Oa=Y)D%gZ$_MBi z1SuJ|!pGCPzKs8H>0kM7v8s6cJ_h@N_D#-D!p*{e2j$4;&u3^+lvDr%zZkI4#oJ9l zBCjivFB|M7@?hbADwVs<3-Za47iW z2YatiGuL1HI8wmUlA@e1SJWH-l^uli%@gDCumdN((*mvP_ zqtWl|3FzT}o=@s=-@AHoB%<2qDUxNrwjqX2&bE2s7`Tyf8n|2h^uQM&NWoV11sYqk z{m&0Bz{aPsoRdE(E35p4pE8mIM|x}HE4H#DMqXateDj4+$KxZDhuso9hOBkI&Rd{N z%hCM!Aj?ksj+|t5Rch}a`{VrsCMT!rmtRh6NK{X~5wB`YVdnIxdG)k9y>FgGpx1Jx zl}6#dcP6JIegimy)&GoBShR=o?iw!!+dVJ3R&HFzH+Pmf0{M8Cy?CekbPYUv+x6Kh zAq=*~xebZ=156C`8h=YTfW?}*-1Lyrs`WA<@WS04rH5Zb*iGkcL{)&`pw=42dcJZe zLRo~=7;$}ix7Tho{{++NxVtQ90t5bSQ;)wE`hD08h)tY3(F$&P;Ja{K^`88nM1Plt zpFiQYiCzws4O!@#Q={;M%b@+;4*4Tfe%`GK#&hVI@B0&@{F?2_z{s`M-727#tIm9f zr5Sc*+cp(Ki6TF@NOkNq9T0Z!gsEiD##t4ja01avSWpr*?0YMowV^-|BLq{`Fu-u1L8v~Rf`^M z$U?AW1wDKf37TyVlvehB!Qupb)y*IZR=jkaahj>zj$DZv)_(Vqr5>Na@=D4IEaoaH z@LM+>4WM7aG9R^4W9YnRe##N?IZ1|1R;tx%+zR)Jgobl4XvR*w3w8}QX!Lyz_?Yf^#4EN=CSR?exdLT_NpI(^y& z>?-hl-{#+rXHw-RK!mB1iPj*kqynJrNDlu?s< zwLDv_i)n=nsvHk{KAQ>0;P$LprsHqZv{uY=m%3zRj9gg&4i9rEDS$cN`M`qOLY~Y+ z8i%;zZJ}J)j18WvIjmqB{yw{<6thxa(%4SioITuI^@n5S!2aYPs}c#?*`v~?$_YsF zl4l7nq4TeqprO26okCpGvc3}DzYNzA8fAG6vZ1nC%JRjip!|j<@hb81d=)Q)1{dAF zw)88o(}7)G*|fU+L+PkgSbx{oXsapx*xZ@#8LA^%8EWOpZ?h_8k3`$`t+lDR(R`BI zECuwUYv!`Ib!@m8VEjbvw&~mK%S`A?fnSPz{x#&{TJ zVzE+3P*Pun;7wi9!wI$UlQ!Yhp@`{>07bRK4BgT4J)OtNZKS=P2pH=6fav+}If;d2 z&2p>d*iNTWd<^s&C=r;mHyL=XAJ=P7V`1Wfn$KtwC3N5B#CzkoN?&aE-c&p6Otsw| zaL!f*L`9bwZC@d>>Db)4aR9II6sM|#wCaDfRe}%}2BU1ZC&z&Y5j41(5@1=iW^jm< zc07MO3!IX!=x~jD(r!xRIjT4E}uhr)LI z9=3r;7~v>`3v}*jQc4uWYrQyoy3&4C8@Z*~MaL*4Qfk~K%`!6pIs0ESEl)fDV?daYc;^@JX;Xpk=XCe_l(^SPI1Pgy2qHvid} zUjQf>stlVM0u@m;B5kKj;*s0Wij0MDCUKs>q7IE=yu!;V!Y8w*3&2 zz3|0t7CZS}PU;~cE_YUUZY?44S5Q<0?|Ke*4BxO(7q0{Nn~nYVp|AB>D^W|?rlT=A z^y)^&ffb=bqaMwJix{DDF$DVz%(brDe(%;Om^Tk|*q~dr`F_<8pAUtX$Jr1`q>S8{ z$sKX!$f#$?F|_Q=Kf9cao|_(+gr7G46Cr0qcvVFA;#tIK&d<9}bYT#L zS@8N1J%B%HoO--%)SZ{jcy`%*xo$n+qzS=+zxqHw1v6}Y9xGm;TWp@5rX8-fb;MdD zuzIZkOJ`%_zIb9lTg&?UZ`AqgTK4pLaqY(rkzzy!*QlR!UJMRG<8{f4YnS=dgeF${ zgGr+>xoxlDV0e-|;e^*Z(8CvQF*Flj_%vTNE^~iyWCw4-o-#O9v{_j=uFdi1O<9fL*sg%w1V|<+MoA)^<6sig&f}V1^43d4- zMQ?pt&%aq{u%)B$JLhN>e*DSS`5Z|$xklmFm%_4Srs}x#%F8dbB%+acR6DG^l9PH5 zV?0#;n@Bg|{k}4vjSYL|KaT@gzv-Y?MPtZfKYRtlE>6tv5{k705NgXJM(di$%1)?Jo2uHFv|!mKzjJjthy)9Zq~)l{w>=84f!slJZT5Cy3jlLsP#OdE}fE zROBtw-Kep;ICk04uI9O-7dthb9L&_t_Nb zoJdmj(v4%hL$LY?Ic3?IfZ+@tMNBJH+cF2#6-Sz*HD!XMF!6Oe97rM^*+2>f1!LPJy{M8R7}F%eJQ@RpTBZE``@-FC(ov;?G;0H z*4$E>^h+KAyV!cWpfedL)&JN@d!bNjaRd;uuRt&7q4qH@St7IGGXqkUq}vQzyQYQ! zt5SM33**$lYE&U1KsGFsda!fp%zWKwT?>sPJ1rm>7vPH*T!_p(x<|}pHOXyiV~=HT z#m+!tR@JI$+MGFD@j6kKW{9QYJ>P?gbcZgWuiD-Qo~hjZ?`yLX z8M#Ekz#&viu?6igB^_muq`u?KR^2`{)twN{M34u^A`v}Hlfl<#pO4Cr#4a0UCtGB{gx*T&)iiA;4Z|P_%06Y&J4m>Z*_7uS}V7>Zbf{%l-ER^U%uUj}3hfWq&?_>tycqAGZT% zD;PhjPKKRL3%AM9Yjc^a%7OfOLsHvDrY7oGWtl!yBiB(-F{}AQtM+&K{NMPY$Q7HU zKH_ARV;{LqeE%+r))!^_Krt#K+>a&?feYM(ORr0vaMWbSg#3BBm34iDH+$q2_fSE? zb~FQ?V|*KcmTKHWeaeJu@Q^L^N$&Rl_wFa75Qp-^>=lJDQ7u;~!Zs6=IcN5LUTD;L zI4M3_ek8Ni^6M+A&#AHBLbNp=>oqvur=yjH1hwz@^VoYSk3kwuhba~qLYEx8az+me z@(3~(IxJ9^<{T2Cii{yp8zvG>JN&ulz@zpLZe&_14J=$-Lp7;s6ABz$Txze)5WPw! z4d!w7Iu=pA&QTm(`F0#!hX=n1(cl+3YBu9wxYd1zU)IU~iIMK1fkval45WAQp`FA7 zYC3EvnfhSs&@k1nOmO31F@rd*wI4>v<)L|ZoKGn)kTii~MV?c0#luX@%?p>=SWpYU z(8C4qnu~Z|(&Egrqeyo5zSLU!F!aqkR=K-g^v(2RY1vx(W%}(OFJM@r^0u^I_l)*u z@kFETFOLz6n|^9Z7np?isnT!mYU^mx(ZrWDWG6Yp%}h`|&thyQ`?|Z4ZJCgB-B9Nj zG*LUNa>^hbonbW3G(m^EjHY4D>~-VpMd&#_%g%{9g64vbikaPdYDLv2TQ^N!=bvvJ zLUA7HGd^L|;%QAv=X#_3qOJ>}O~M49iNSx6Dex__i!a9;QA&SKTg^zl7|3wDj za*p;-qB??C=jX5cUfZgtSM;U_F!XFO1oa;nD|>~>shy#FN{)@jxBQ&cll(6bpxTcxMdQ?|maBfSWV^J+(b5PR$?CbGV>vOfP<)L{6kx0A9w>(I<%PTEFJ zc;xrhR<;GN9P-YgZ+gZ?J6@oc>w9ikIwjHI)}BWAyrS$*v@)rCoFc}|B;H0oYsX_7q-97eFD&OVd_X& ziePI_{`ZR{f~^T#uiJfs*RsdW&s8L>mzPVs>BKklezd#dM!j7B)1<;03fCtn&q~YI z(JY#&D_v&$$BFLwuyG#$;dj7i^RsM$4ZcnNVfZ1C^l|^Aw9?9US&k#l@%a_F42}v6x0?bCu>`8&1MVE4VjJ+D1u4)A=y~Uu0QnXJ~~x7pXqq zJ%5b5YU+3YmB8N;Q30R3tK2Z(E1%@UsFUvDhk`+&{X(+<;tnAcbO=HT8i^lHmF2U_91++HK7 z441EW~stV9@#(E{mGar8j@;=Rc_QvjvX8NbeIud6 zL|o@Ar1q;_B_KM$$GjMmDjjxL21gd{-(YP=mm{+p%H}}19i5ZbbNb|igZ!*-{PZD) z57+klQ^jDH(S9k$O&$}nj7JS^J;J$7$DeilRj?QG^1guQ)6cd{wVlY5x;Is#tJD$S z?pRS>)y@J}i9LAO$XP;J(7f)tv(WDqom2BtJo&S44L9i+G8BV&M8x8*z2ne9S6a|l~tQ$ zowz$d)i}upfCf}^se#iQ|I}pa^TZ-2Fe}X63cMhdt<|xy^JH=NK|$8WP(4M!=~}7jhQ33 zHMO;nlG1{_HbQp`s)ZJA6t!B)8^~TUjT@VU0172TS!CuU3ZpzIi68#WBY_@5&p@kn zSw*7?k}yi@Tf=_&X}92VO9)xyr1c=%VT^R)RKZgRW-}Q$sCgxW#b!ZNs$0_qT9hYP z?tlB^6M^)L;F6}Pj>(j~QFH(=Z+u%Gcw1dgegsv)b}m`tMly$>1g_{KCOW~U9^tJ* zzw~8MD>YfXl2v&mmQi*#ESM(ZqU5U*X-9(XX5y` z{cZ3zxY@*Rr@0P4c})Ws#K(w8cB>zgB`~EvsE7hf5#_JpsMX(YmC#<;071HsOkyqO za+|UV-g4Kv(!P`-d?@BnwjjOOnvL4ta-)Es?}7&ADQ>g6c#oEzzdkhhkFQp&L2U=wpP?4=i4kC|SV>%Ot*hxgZ*b^HGb@KTs*b&39Zi(YL%Oy1zIs`#@@)A>12 z{^uEN!1nH_H~9!@9*&?0l={)7$>XR!4*rC3c1M>}ha zDncTs&u@uA3o1{{uXA$lS;=4AQAx<-Ea_-XBth3?mD3j#_ZLt=%W`VC=^Ysin!Vzm z$SuS&XkGj}vz%S2$wP=rE5f}mNH5@dPiFM#%_+f2sI8m0(1GaYw+NXfEG4<{&Mgwecb`DWkbB&c1D zZA4)O3OxYqW`MEZ{RP&ETikF@@^<&amErdXHXD+j10A=EH;4+}IZW_FLUCH2f_ven zCP}{kSS>TlMyVJ%-M*Fma>j4_)~NzJ+?dqyY(1CXMf@X^kk!|6;p~I+^U)z*eun|z2vVQ3oL)!T}zL2g6 zKiiGnt#@!5jf;z8msObCej+}2U<@bug-HuXGOLCWm-AFf^#hnXvWZxyf9D@|rF60j zOHJz1X3L1CFKb>>PH!a9%`8tkv6rdM5{baWsvBo*&+2GwOcqPr`x1pe8w>W#$D>c$ zb%Nn)Vyx}A%%BY5hh@wi10+q?YakC;%%zE(VNATXiS7L=>c-up7cWR2i#8K^)`eA_ zX|a5BIoMBWMZ@_~lZVd1()mCXy_jP6e5zfcqcyDuI_$jnl{*jEe$8D;U2&*OFR@(C zFy+KP`&!s4`(L|ZRf3AcR4J%Q8UVL4@Gqx^w>3;p9e%Iv|IKYPkJaA70-2KuSc|~7 zujun~>m9EBB;Qo8X!K!jA8PX}=rEP}bVrUD7g}$1WOLcy zH0^l4e=i;LI5@!;_+$L!o!`x9qu5goBb$61vO)Le|$P zNqIoERkuV@GzCL;+Sp~T5xf5_%5Ibnd^(AW3p0r!fkSgW&KS z%aHrHB8yYR={oco5S=9h>L0aU>kz8YYb<)5+$gzpH}Cn1sv?A#m{6gO^9(Np1t0QIX~yV-e#mY#|uFf{L&HP0G6CmMtR&{knf2>O7y1*Z3)|Y z);ez@(iY?d>-;K48cJ!EGn70GISw9C3_F;M!otegD|7`-iAq8py36eFXV>IPubvPyyRQhw661R;S6n5jKC7s{wz?yLpmh_tX zAH2Qe&cdlEx3`n=a^Z5S2O5AFb37YtZcY-L7;G-(3W!nw@Tx5;p-0f!@oiz=@#Ko8 z?gm~7r$jR`Es<0Vz=*PY=-hR1jAci1#+6&ZKJ@R8Aj1oE?TCOmE>DYvgB*z!H3qi9 zBK6A%W}|#o+*77958sps&Ke45w-*nGFc{Ugz*)>&l*vtRhWla_wWvKCPKk`c7GbG&w@>=wPK+)}&qJz8)bw((-W=9Y8yQ-l+X6V`#5){_j6|9K z0FyI8wRhl$ZMMVm*vw7P_@w0u4$FCBA2XSUV9NT;t7$o&9UEH(K21J3z*_ns zME8+nI>EcXM3UthZ)1Oh?mfePHe(2&*oIe+_9R`UlDB+iApV#@=c3yX-A+hqz2)7} zl21r*kdd>~1MkraRg5ost?z@VhXeiq%UZSLu;7SxB(xOZ1 zu^u{BwKqiu?PE?tk7K`qKkTs;y=gy+z){2@$>(uO~fx7(3 z1V>cQ6M9}dzR)Qk<83G=%)}CGma$zM5D*}z)9HAcgGOg5u&m!6vblmrM5hoTgxC)+ z21l*Y$)XdOxqK#J^3>(#%`7< zL2B334%%j9K>w0^m1q7&{LST1f4Z9XbOwCjP?~J z{`;N<2$AfwNJdV=&H^e(D7|5TRfVf2V`k>j0*a$Tj!?*d7nmace)>e>Sgt^dOJGFe ziUa&4kjXsa+*sc`Jo^EI1VgaG|Gm%o_0nO4)=N)&(%T-5WI=g2ox(-JCu{z^x*drf z&Ahq3kL@kj+*TWa7>hhV4zOK2JNv8H4UWU~E?1vWcijvDf_i(R8?_B(-KvXmaxX{8 zY&j^f#;VElJ+ns)EU-1<0T~XSn6!G`mLoM?1q7o(a}-n1U`lk0>r|blsoZGf6a%vT z<)Qa<580V*m?Lms*=41`v3hMh>8emy>dFw?iNa+?FZl7Ei-R^rN}3Qvmke3&Mz+9!%j8ji)L(%?wdxgq?Sw!4cBMmH^rwV zcl#C}2OJBTI4)^&J&znduC2=K+EiB(m0^5!dw$&qQ>P&s3gOu~_f4 zC5pUPw=A)j&A-3joR4fVsgyqyHea3FFYzmGTAa0(3)b`yJ2_Rbe1|hq5k* zZvO>)o}J-d%xKUTT#L!NWBOCGM4SI2g(?Y=!UP*`dX^?Y9V@tG{k>>wBy0o3V?3ZR@lnAtp)Cg90<+Qt>zTnniE zaq^kNQE#%%+cllXUQQqlrgfB2b+bMvS6?@j2vw(r0!*FcsFW$sBp%A`?QvC4tGXu_ z4;*_A?OI*}Lus^a&pJQtquif!{1Uef_T>8K8IKKFi7C(`c9h zb6E>Zm{B#xP-){OWJM{>@Uinye`^&M>?efN1M^3HkRf;l_=dUVNHrHsB}1$<*yK{nZPEf_;&XsW_DtjgDZ z525wBN2CCFa9^7=jaEN(?_siqNS++21|A0rUnqV47x_Qm(p25a7d8#ui1zw~7OBt* z=orsVB4_e4!NiP1E=l+J1VxDzk=rmfl>|%{ls0i7tswqs*?oNoHqg)l$dFF8AmXjQ zyF*`DK0dq!i5#NbDxpwRL^xAk^FfH3Gv~R;xF%l8$OjTMf)cDGa00>L9qVly#=$9# z1R&Ktr2*(#gKAOGnvYJnOpKmkD34p{t$Ugq1-^maZ6*P1V;gp~eO$Rh6mUTa%hLnN zOLP-O*kzVTx5p&@6S;|snig}zT05WG-S~V@74oZqOQFvF$L6SXQuxi65G{4t0ug1Y zj511yOh45~?w5Dj=crZZ>bS{8YH=9_G}S6v$*Sr4->o5$=RJCY;BK?N)*QUfFOSPA zm!!McIjVAUeY7bLRbSRyAIyqZ5vx8T%psUxDeICFqI@~0!U&CkDMwm-&&bFjB3d9Q z>z`_FwUK(T`gRV&{KS>2&uKW-2PXD&j1805Qdr&O02Z-}Z*GyGM%gcYnXGj6-aS6m zwA2kIM8wzV1}(4(pgf*Kv?(-81C`#hfpQYT=~RI4nVS|_FKuztCTV=P3>qy|s+_|N zKJgI^G-4yJ9M8>XNr#aze%W1f4RiE0(&dRV{2St#vWBK3GbFVcDpL`k5=4MvqT?|Ze2tK&`-5Y6psI4&{&Onc-YU6 zvcCA+tyP0Z#rBg^yp|e|v@n}=^l#Skzo^jnE;ZPzz30WqMPf<`QfdeUejz)Os;*#Xa|5TV?T}ejhSi zg1%kFmOpE=pVj~@`05Gx3AI-@HW;t5@@c*)*Qrl$_r0mHxUhWxzI zn?y@V!jEV?4+S}9jE=K8v#A`>XQqXnY#>!P(!pRBfk{arQCf;L4*8<_z(h$TCIt`D zi>Gy~Kap+>NZhkAD~`&lh+rV+LBDi4jLC-*O3SnPcwcu7^d{H8$!NlgA3W|e=?Tqr zrmIWUW7rW?s@go*V$NKaHnyLlAZZOqUAXM~TO@$b!^se;LKyPd($+Y*9zuKlI*_oS zu;pcJQ&fS^6$Z^jDcu!KVxexW#E=c3n6Pppw|-#Cc-FjXr9??HaaQk2DzlVg8mL`` zvplMTowqjM;1kyfvwwBnb_)&LriITBo|bAH4(;aWG~w z{gMXm!o@lQ4WtVR+Uqoe{R2$=iRDP#V6adu@ zkki^6$b?{c(=)aFtBbai%frLcz>b0kyZrlvE?fDPmQm|@m4vyO$_5`Fd#h!c1V2s( zL)Y{fM`f@Q!0mVukINPZFq+mA&Y-5<;rxlBe6@QB&3C@$Nm}^f@ju%+3S-xG%Gnbn zlL61Q+N}Y#%qHg;oJI$y6H!7D1Jo^Jw>MD8ju?TrsGmN1_r|^;viug%>8mXjA%~Cm@TM1kT4Cb5)Wsyo@i6)q^d6oA!yOF^YtbCm{s0~MrJj& znsH|-epi1<`{?qUB5ZF$Ot5$^7wy`A6)~KIJ!A-r@9?HkT={(tOSLA{bt}~K|Flak zAf3yPJV~W};bFAsi8(&AF9E9D_4DGAfd5M;a!>S>*2|mAqhujY<1{<)FcC{&fGbf^ zxzTDyFB8?Y39uU2|2uwynw)9qlS)G{Q&EO$Uw2PRksBf{^cYy*HQ8>IQ-NBm)O6!s z-yOw?6YCG26rbn`+wy^1dyFQv80@vvycf4eg^Y=6cY@14k+s!fWqKMs`1tLCqV3|e zt>Obuv`&K+af-nsQq=4#BenxCO>0V<5v|hU0$Sj#>fgLWKCq1QjK^~o*;E~5Vw5TT zc7l|{in2c3Fp?&9H{A>Cv@2ytN9Cz zWhKj)RH(udTD{BmHK(UBo=9{5*6NA3RZiD|^K0?(Ke0(y$^%9tH{M)By0e&mhduY~ zA-EmhE6JRxKaFGR+^*y=w5WZ({gjWq4Uhl=Od0S`E&b>S7Tv7Evy%yo0y)5AhHsWN zb9N=Otu|+>oNaTZae|aaKXDvnuv1-J^lA6Uo$C(|PiqgA{h?vXETgzCC@cYwc+LJD z`#(ILRa6{Iw5`HyF0<1L4#))+@0XT-QC^YgS)%mIp?l*-ut<` z_pYk1qR{T};vQtAuMjT9Pl-Zf9EnoH&X=LpAre{ZKkIF^3N?W>9VrA}JbTQx*-Lo~!q9{&cf~Z)8WybbZ3cRnxCI7{Hx~s;RSV zWM%}d$%R_x)~363@A^fT-Mz!pv9|E?Z6BWo)}W_0*sgc4XS6JCb;SJV$P5h6@Yi|R z>lCrmZyC95$zF{b+!>#-p~#Vi$kEbp7HC3}@Y1v-oYpIPOY~p9WaAY+2mfA`5v>kG zm|)u0l0+ElbJzrOgJKOP=c)mcxNDcE+={hRA;RtJjoK@Q7M2q3g?0~ow;GK9UIf=P z+sv4hz&`_m<-Fdk5ZU-D8Ziup6aIcI53#ab?hBmn*LPvPEeM2su|?6V!nw{?x}MjB zHkn$hkQhu(ccWru8zv74*SU6eu0nLO30A}B9XZ-H$*=9iiyP_J9T{}vNpf~YWT>QA zLN3Poq{7US+uCT%^~zY;YCF4EaRSSkYi&&;%kl*zCAkG7Coo*GT*qj4ye$cna_3fo zUgM909~A&I4ph~@buMvMF`l~6(5885^i02x;B)zrlp(LOak=-b_p9AReA!cP$Nz0j zvdj;4zwPVILDOUOyhwRB^7W1F3P$Hz=&hkSD}Fq*BjqusZz9wiETSn&N1NE5-DYGC zI^umV{pC#l`Q=5muy;)0QnioAU4`$OHNo0g(Ehhqc~Anxf}!bwGYV@Vx6xA|^GUv0 zxx?4`XwK^Ippom%(R6JJ#Mi< zFo~Z%@UaKh3Tw?wRx8V2RaA7QsGYUlG1=>igmH~o9t>}(+ZVlmNyutcpKO=4-ri9s z`cwwvy!n@|lMX(;epz(*$AC%-7|)K|e>^(TYZrcww~k`RmYsT_L?Pcq2e(RJBKrOXcxf`>= zyN2mOfMcFg^V8;pQtj){BY^kh`*pw2h7Ik(oM30L^OSM$pqKm}UlZ@v(OFPo36^hr zX4q~`OL9-};oH_`w8d%ppSi>N*e z&-BanjVRp|B@rd67a+1(9-9_MgUiqChDrbJ9TZ2uu`fl|R=PPSyq*^kn_*%iP`wp} zvaGe-nqTD|%4KnD5Zk0NbwB%=Lys~?=r_~9xxHNL0GKqOzLrH ze|%y)%Y4cvt*!d@Y0j<$>!J@#(k#ty>e20-hIoY_)YNvwQPNZ;7gUZ7sF=iBA`%M7 zfN=I76Bb-}+Z@urU&Fxawhlh`xJo#O4$gF^gq((x)1R;rjlM@wQXPtm*zv{x1&%1> z%caQ;l_agMETgqGKf#ek{7CT4`jvk-Ted&)>%KmQ7)N$73W@FXWc-qLYCW$e{3vgr zn@kKy_bX`DX8a9CP@WUpx_eLr`JvOC@2kW-{6fiJuq}MgAw4>bogTj-OL*pag(aO6XtG3wF6* zTWq~3{^FCSSohrSP5BC>Z$pr(j5AY~0e-r9jolYnSl(@#pugdKm5)5K$)bgLsLdgdGkWv;5M5jywtiHQ%RkdfWI#Qb!`&$RiI)Y7T;2SMMF zuCmIthf=IKc*_bGR?__*9x`0(<;~F(t-dyY`4EE-f^g=7qTxX=2{1ACR6UZ>J~}_mrOOyM{JfIA<3(j3SPX^d#^ruZOHJp z{AiJ(*NpogF3BFInKfi&+^V&r*%Kb+6-4fkYQqCW{th5sF|$xd>-1gKPz zx6)5+_5OaU^)O+Hn!)T{<^PeTj$&oy7Ht6m(S1ej%t;`%KYNrJ9s5Y?TZ7~NNk@GH zxT)qy9t>7fH5U{qe3ht@dDWuD0(c*8+udV8?MMW(u_Y2b9*xzYk4L9F;{r3nhR^wjTY9+Kohj+5hZB&i zW%5azhwV=lul>{?p^%Kx1j>(3df{x`oIU-+`c+SH(c-@-QK?dBm~MU+&ye|JC+0)* zl0plW_d?H^w*Q^A5ie40lfYNX-aMZDD)X+}|JoHr0mhFNbqI(YhN~ z=w}$L(=#dVlYS)gL(>B-0_$q&>cQ^m&@c)^6DDpqhb!B@C??xCQ}j{TuxXwAuApmDHGC$%w(paDxm77INhNrP%HxO*6>`f zvV!nf*Qz_*sT_%A#fDl{Y(idUT?84)%8HTQ`X`QSeUJO}-jw61oCta)bHc(v=XgyI zjhtfMTiz^t`vS)kU-%?(uW`T#?%?jCo|R+L(87Ys!;?DU0NK711+NAiVZRn3QlS9*16YfU;GSA8Yxa*?Q+~tJ{B6yoL+>n&c@;b9 z?BtTGzg8eat&?&f+PtH_v7)SN57MLZ&8!`^mfY^QwOVb(lH8kLY-;&;vL6y$qbc?J z%nwdUFG@IuS7T_dm5faEs34o=vtI)`+AUw{eU zq#6<#WP;FLpe1DknUv$R5$8Qw-xVii%49Sr>F@K2jOGy@sqq^3bGy$1?zR@k^%2G( zt%3T^Tbm8?C~K_-yTGf!K*90{Z>lWs8-jDD*IyDyiL73Gf(4+o?pit(t-G^lUZ{^s zbE|+Xo;#kDV5=^Uu|YXUijYQg;V^zeR{_VUi-usXd)Z<1;5$-y1ya~PvLBQk#A-Dgnqt!u|cRe^HnFw6PPnZCbDAzY#eev zOl2w4VPvww84Xkl5Tv3$k@_6sHyDIPxw*8NJ#peu#=JHuaBh@Y2F{kf8N*PO4NVeE@fj%hf`FP*ZPn!yP6cu+&=M@ z`Y3@nLAaSO%0o%<+tU`#a=hu4ZzV2?U8FvP&{2bBabBt4c_7(W*|Dv|>G9cP$Mi3J zke8f!#Xmm%#p9kHK5@g)mlek2pQDR2pX1}dUk%j-)gJ znIo|<5;9r$R_x};a5)d(nUBBYBqoy<9Y$iWYw86|6r3nwBpi5T;tfLw4f~VpciUDl z@n<1cF2P67qm#+ws@o)-%C$c-`bi zEOFZNCewVYQW0lq9^iksrgvmJ`>5tcLSu@^*QoRqEi>W#q zg95shW1S=bxRlObKUDa~-ePo9PGVkYyWw+5<7Z!>`j1 zUI~o#D?IRsHX8pL@ya?##f>Arsfv)ns;KR1TVPlha`}n~nC&+qbN0ItQE& zEiYOft|r!&>RemXr^ zo&OrhZ0>Sm8I%HP+QR&4Wk)qGpTNsmKhGUzU0OR{RHWdCt!(AT#EC}4nam>mpc!uF ziU}(v)A;v3gmzRB*i$b!uD4l>wo!BIDS%7LFU)Fi5!*NF+Tjpo#ZtCCIG z8jTCxmsm;?yW)LimAZ)wPb=Kbb7}HP9*VkG<|9)Y2Dwi+F_%4eBQ+7erkmVf@p|z< z)3%l>Csp~~tFfa^pX)xVtzLx9uSZ2CnxvxI8 z)w+nX{cruGwL*#d6F!lS$?;x9O$FH#E;asADq`}C-|Sa&CUDe{^M?6T0BkgS7KU!< z^>pWF)p)l7((YhI_eT+}4aP*r^<)-4|LBD8-~Gp0SSro#34D2-LuZog9k-`UeA_*v z;_&RQXHwGA1)ZTY7H3W`i}I1A`~znsfNJLz_mkx}A%C6rZoe_odGD&gIRhJ$xqThY zDsL<@zuEwhuznHohTpwPBBN*4=bClny`4un5%Rk1wTES-MdHm>FPFqcZyv2IB)@ZU|;!+$tX66SfK?X_P`K%QxGElQz0$~sfWHa_3A>^}9v-#3<#}5PbR#VKoy6nJZs3an}e`*77HR;<<^;BbNu37*|>Y>r@H@N3GD#57tRJzEr6mMP(CmF~r+%?4> zzFkI|BQt$EuPY`3;4}Mh0S*cwS8q4?KYt6m=onNMq+(jn7)kX6Z3G3`O=oshP(pYM zrG(N;1`Wz`)V`@4XVo%A^&DRww1QT#%3fKP(fnP`T!bG-^kK3!{9kV7*g@4DLa^0> z=A?L3*XGuGkW_l@WX}Zy(_;}(=5B2=t6*x;g&AT-|MfLQDYD+%TUH{UKjS2fo*8ud zEAw`scTlc_jvV_!aI#E^G^ub;~a5w-|HCVx}-BhorIiDl8qZU)5AFxZ82X{y?qcOo}uvr{DvfhggI0$m%}TZk|n5Z(jue; z;nPf2=?}aOoIJj#vO0P;jdj?a_2n&WgY)tSr9e6U#ayeZTjWfIef9ni2| zH;-4tLtaMeDlNhwIXY&$ebKAVonWo?=h^s5&dLD@+RFJT3PQ=3-Cuh7L$~{a&5+7z z3tVB=J6xQOrY32buD3N|Tt^9h;XI3xwUG!)CPRph={oFrTTDBgn$`dM=xHaqIc3qk zBozduQ@xy#qh2JMtjxf79+)b9yZm4oMk}MDl8_;;4tCvJ@8J1AL0{3B9bs1ilTNuQ z&NOq&(|Wrn_5RaRO?B$v3PYU1!@0#ft|Rhd&-yRDllAJj44u15>ubBuEj;Hcl?;Xe zkrh-7Y>#ByE$@N(z>~%Ltj;pnrr!$2ezf^+==1BN`@-475zX{)N&dcg;V2QTZ0za*D(?h|VC9q~ zxL=fH@gAD<+{niqzszdzs(%i#w`<;TlZ|VShBXM&+yD{pdz?JdHG6X#DY`L-vAda7 zy?s%DM=&E_@PRBHrMen0J{oVEOD(7XCoV5|B#PtEbPnzNioXljdEXihP;+SrxvE}9 z85Pt)il3}wY;GKtTPL*ECdBJ-L5oJA>f)Ly-7_v`X~i0HuTHw<_=MDsqOcvhC|F)% z;P_%iy^$W#x%h&z+;ILo4JyEGuAc19*55Tts6iyPTN5N_Xk>RhcKeJW2pOVa)Ee04 zMQISNX}sc%2sJviLFMm1irBcMERCnhHaijUz>+QbAUcH~kmTjwj1SxX@=1oPfL4j& zjh5zgN{jr%)1DA!aLcx!OfY5oc%^jN)qljOPdAF5h8L$i1e+GZP%e>#&S<*!uU6xR zuq~Mm31I%#LS|%XH6}pDXz~(%$mscQA}NMA#?C>Kc zWTxKsrf=0wq0Ms+$g$HVPv~A?m!Upev7t=sX7})PD_)`hiLq~$1Iww&3&hg;>{d82 zN$zqCNS;#JWB2L8EEx5H2A}(M1>6ho1#($yVxV`n-V5XS)P~%5@D2}@bnNEh7}QAI zobQngEWO|IMG^~)4OuVn`s^|TGFrwp0O{MEn^-5yub);Le8;HY#U3hzI`?iv7ppf} ziPX=xucI2S-UN;{pZ4h2wI2xV$KT^6pzCUt4x3(#$qn&*9P7sYy}@!MJQaj-=InMi zlzXG8EO$g+`7En~;(oumfzx9Z8V0LAK8_C~Xvo~Sd&Uu3w2n7|>8Fm>TpE!zg$iaz z2SeUBdtVq+nu79cHjI{9?={)IaFO<5K$a7NVKkEQ^0{4l%FN^icGAKVFK|2p{SJPs z@UV|6rYn1*QC)sUODus#tm~Doe$u`4XYDt%Xd@KLA)2fNfH*I23cE`qnpg;!!`KuJ z9_36jYkdu$&l@>66x1`}Oe^$^+_hry8-Iewa$#O<6iX_#?jWqq(odu2?j2b5?k6H2 zB=SE>y{J6gG63sm@%1~rZ;QDf=wDm^Ijo5qA*QfXME4yfg~nvJjr#lzJw+oXMh+Yk za^)ngW)_>M)5)S1gPp%hLH8t_<#lW%ct(AQAV4rv`+Xz|prX9`p86aX(5mR9FUepk z_b`9v;X(SH5oQxX{7e6}Q)dGA{la)~T2Va2jtbg$ma>QkyH^x-{}d=@hytfjd_5)-a3gD^rN=0_ zc>IF`jHlHeWfBbtRLUzE4XP-_RDPV@f1k8&3VP-zA-{}KB+rB7*i?^X#kT%okzZT5 z_(e>4tcLHEq%`l@>d2ZhdYvCu0X3T@s|REz)NR*c_M zs$3jqGU!Db$}KWhr9Yo+i$lMk5@?f>v#LT@EuAE79L)A23GFj zqAMZ-JJS7^9m^}-e&A@OQ?_T9-ISKpzF)~4K8f!h>c`=s@ZnL zKML2Rr$DWom&(dsh%3Ur=4PtVyisaJW*myShoA1gk;`LaiEj|F7lszRGJx|ITK;C-c|Z z$x6Lcmw)H$R%23|&V8ldv+y0f47OCGGg;bOm3YVzm{(YU@v;+x$>Tne z=|cU<;6Fz`p#B6yO6i%t2fkX6&2MKl;wfm!s>-MMdILIWajV7A};qJ;HmGjA-M)%ME_ zYwzMPJ?eLa;w3A4)E7vwpaM2~8ReNWEI_$D8BftCdTyoLzU9VXauD2$bNNj@7u`c? z2}j&C5hGJc!Q;vKa+HDm3$nz9`F~6;o){VG!x{hJE_HD=NJE?$I73>LAib1Dtn8cv zdbO?#7?Ku_u6oCp^cJ_=&<2`l9!+ON=1GOS@+V#TuFiKd;C$QDMpITGt0)uu3Yv8S zH&wDRg21x+uP=LcgaDx-rP8ZNfb{Ob7rwC18z|%_nHc9CxCUJb2bjLi#E@)=fFy}L z+dNO9Pa14AqaA9I44ccKOrsjQ*I@_s2ba`;y@q)W)SC?Y`$`NdA{s0BP>y67+RQnB z&PrCnC0eV221V;56_Qsp4UcW2q|nG-o^JbcE$sK&Z%I}5#w@PVgGV*5NUwz-e&v@W zUe8-(v6@V=@3l3BL@oG@31pp_T~?ELS6`uLRS5j{`=@d8bVTFZ>=XxE^>3AI@AEyJ z0zck+N4(=!ZImvJ596$0m+H5ra#_z`^x+v)+AOi-GQsFW;Ok@ockUXC3Dd37CAoC! zNELH-*CX8mh0KB8su}`-CvKeNg!yzMUpS$#zyE6}V*Y%&=LY6;w64lD$$a;e2(X(X zVO4+4+auS4ryz=Ge3dRYg~Jy6+FagZ_3tKQx)2dS0}WR$V=SlWT9eQHPLX8tZAcIS%zW-++e9<5>zU*lQ-zuz zzy$mOmXGzgl8RylbA2JWaMX;f(1dPgU2E`)uI_Rr6NtxYuf>6rWu!<^ z&*IbujZjWlUTcrTPVVH_8_^d&Fi*(vjl!L7KZ*sMBSTRkjxq({ z$j(JO7o^?n3p`))6pVN6MqiI zlcq?khQ8r*5|8D#5{Gf*(0S`q9X*82{{8xQkcx{Y7}*xL!#p9ndL{8GH%cX;STrt| zn#+YQBlT`~KMxMZ0WOkm84D_q2OryE(yM*lcRLeJA_6Jsvw={-+pET;7ByK{Hr8l2 z{1rPM#++=M6A$LKY@QL%m52J6O~8eRs{saGtk+xmdsH-GXORg*_NcgA52c%MGkd0e zeQzr8=ZU}4?-24PHmvq<%(fE2@8a~Li zV9K>KXJ&j)-JEx4*c>vW6el&!)L~#O^cC}1m-sCdk=sr{w(4JsN0)bk54Fm83Kt}l z0^Tu=%O3~LwZ`Q^FTb5L_hj5mI%@`N$H`lnlZuGluoAE*O`=N=d4$WTNdLX#3*OC# z#SX4>c%$Uxv3HxaeThv&hQh9~%^`0LGk?~M{WE7o5RvHPO9u{P&Nmm#aorJT^C*K@ zyQ)wWpygMr%qYXm+3nsD+ZtzaT9{&61=rq1fxS62y&1k}?m`T10Hp6vp%JAWNsRPy zf%LEcku{VD4xGt3fl`gu?u6LLV*mUJbC!BG%vr$LKmzB0O!#Ih7(4?3G%^{`rzwpa z*Qs2ImCt$B&Vx|BVA(S#PZyXGe*d(*5?bq_F=s$@E1VYG=bZ88Zf*7o-2YA0 z3Gg;8BV+?OeCh z>`T^>DHJb`6^k7o@Mj;;ImXTSK%qqLJ}4LdosJ*!o2Dx0%K#<`AxP4R8UzzIAE#05 z)|-3kPX!jqpNtGUrfRKB<-WI#&z8(U_&raHDi$IOT=}PqvxUpj4rYoa@U$DwL|3?D zN3EssUQrR72@i5NifTj;h91CNbB9qsF!C}o99&$xdIogJ$C~*Xug-!}N>i@uJ4J<4 zS<^rkZ6I}Jgsv)nQc67Zbp0PLl59qY65?U+U9q!q;_GqvWujZb0|}Uzdc8A2%9*`* z^k>CvODqWT<^M!fG4x8m%+$tZZH;^0YSl-}){2`aI>3@_HE21FSV?0E7pmpLa{b-o zp;ac-vB~iTL68_Avo_JAu?@$sdA*?3nH-L!EK2lrb&5#7^w!kw;F6`})ClDx)s6(J z{zRe5y7QqrC5Hg3pl4 z!|;k3INj0#NRtml%3ZZ_8ExO(fdWH|CBdfJ!p>s*fGyQINv!FX)gS7<-SjNi7bd@P zIR_aiUGhX0h}y*0dY}_e$#n*uta=*m&Z0OA0G0`P9rm^83(JMJpK2%-*07x(YG}tp zdY!qbH6T&s|Yhx6gIJiEwS*HeBMk`Y)_>0euyGF#I9Io1xCOkdnv{%6L}^Rog50@tVw(9U8YB{S5qC5^(gB1p7PuUah5 zt+sR{pdTf5=1+FG&%%#C?a4K_RFQZzh-Jhq}UAraUgm&WG_t#ue$TOQdAdmWxoiNIGG;4xE0E3CEUF(OFnmX@hW4;j$-~P}Mz}8s4Y%-rc?uhh2s5+0YEnvl*{&;&L&aad{EOWxjNX00Xj`M}T6fQ*M;9zFQ@*{r+8g~7)p!dfq= zvKFJ;8Co@(^iTiFg0G_qOiG?LwMB;ObjmK;)q{3<2ahXob~nl$!QN$*BV_!h)tCSP zAoy$ia~b9Jj{7!ExZzc8mt4vc)KO(EnRQ9Q+s*U@PDe7z)p$B@U5*eCpd>cHTKf*S zegMD(Wce(Y9Lph3X+&xyD($`{_oXl2; zO46q8u&PQ*rc?-j%y57xeV=pRA)yOPE;#c&{U!jJLc=ZBw*ie-&ddJ^%&w)uGdX8W zTR4LS){2#oxZC?OM2C{TQ04@=Jbs-R#6N_s-E z+9=?7UDx>qX=mEl4T&YbRU1@>R|6^eOYti6t-WleW^>4hQcYN7@o9MmA`)!*K?Gaj`(yd{&WUoU)Q?b9gX zOppRR>CGYkuY2Lz?CdcLOqHxSCleGB{sTyR2@7?mr3n#%Y2$~r#4Pb!K{7pc_S9N$ z7=lI`@b4Q)X#HzzAU8nX@s;^u5WkI_MqDQhTqOH#`w5d#N8z8U+-ItUzPx_8>hjRK zSgWQK^uMEJ@a$)cV%1J24|c7jDBATsa;+8MXS;Az-hcv%*idV8<2Cggh}^7F0|)Mm zJBHrJ;GbL!gO+p!Ks{~wL6e`OpSN)HLFN7MRGC$Fgp0uVFZ=A7e=-?R7rM=S5 ze=9_6rPTl42QcL~xJxOSn>d1G`O)5!?Z1!w9%23tV9;dmil>rN&V!f^thQ@H-%fTc zB%;93l=-FDA%j5XCq^vz10(VUEfb;TMun|cBqLaenoIjZrW6h5Ge4V!^|y^ToBuQ3 zZ=O(NNqBtS)uGK~&J4Q^rMwYb^VWLo!wuj*H``D22@@y_k7)RASoi~7pyAYb;VxrK z``ZeSEtSJHw;Ob#rQzH#>7muyWz=7#!AUqDj)!q!Pe8G-quFW*4N`%$pZRb0{;E6qE141KiDjp!u>F5aE)khR%1E&lRFlI5 zl`JxIJai^8Hcq)eSCgv&Yfcb2gOQ>oE&cPuX6!7?|15FnL8$Tv9o&WS7(}T?dwEML ziRZu~%J65~QI5~RMtG?BSIuhJ)aAGAWG^;tW-^DJ}P zA+Z~jW#Zegg3-(?~~PRH=zj<*|Hm}vhnqzcCxX(d8E}qIdAHsk(p(Xl9x%V z&GV)qt*IB3jd8;Afw$WXt`VFfll*uYvAVsb>Brk~A>3RVC zyiX%j&5H2IZYa$Xv0v&~)fc*SuhgDHbgm?dD_&nfW=WNHIZcw&lNIg+CTFd+MYvKL zbFKAs2x?irj_oJ%`}snx>%_s*`iSENEPkL*@YmS9=uuHyE30x?9>ccXj)bmo`)0|O^M$Y&tplMXMI;hHd zzxv@iO7rTGT~aQqdv-|{>^wv*jK(`S$^)=?dI4!xnsPDBll)r))nBY1k+gRB(nv*S znQSZ!ELHELGrW9yIH*Zre0FGxZUb!gLXv69AjGCIeCwe9^ zpCdmly1392JY|1lZi$9w9&t3#=&v76bTZV)ww)s6oEVL?kMP=)F1)VKn8Fv=U_NSi zILg;5V1Wut_kZRnpbILDib~3XligB)Oza;q3v0apx?J|DPgQkM>6a*XY|5fP)=ih) z)yf=sRfF-9>?#t>fxQZ;?CB}ap{&j#Xw+j)=3AUd1>@C5H*i>z5p~APH<@y&tjXE- z$R@p=5M)BuuuZXkcE=ZN$tdFQ?P+rF?VnPFOoY|<3V-1$OL=E% zr9Pq5k8|bHi&OL!e<4E$BNF%B!VGvA6UD$*fZX0(Uh6vswlxyn?9Nq=D3o3xIH%iN z1}Zy=5ZqD8n--R|v}2B^tghI7{gQ?_*E4v_RjEL6-#pgA5- ztF?bc)rc*TX7CkNg1wK`21G+C&6wL?gZ?Ps?p`G4JZKoBs-f!;s%#6q&nf<&sjCDUhhBW*=oG^oI+tj3 zR<8fhd}lgR{KKvMJywkjuF~RIsor+AFLNz)3A-{5MaK=j_FeX+!Om==y$#NGWqf>0 zXNe|K>i*Pdds*!SxtRJPuWvmOWlPxc#-JhL&*_)NO1m#G7k8D(wn(3{eaSm+t8T`@ z*|C3G-1kgoeGmR;#Lpf4CfmhxS?^RUJMi_kNTwru-#&7mn;hT$2O|v*Kh+%{ER-~e zN`=U;KkKY2Fy9gCF<{YjHA|10xB zZ(^^D_|Nh~w?58S8i`%Dxs)VS-Q}qnU{UF3LZN84N3VUu73HLN3hcsZOn1zv4>u>{ ze=vFuxD5ZxEtE6A33m)n<%aOtvzVQ&kg*xf8;68vjsCmLO}V`jTz_(jzy#PI1X&^D zb43Dc@Yw8@Mf*YEG&3@Lvw;N~UZ<^(L~alt>j?~D{hFBkEblH@xkI-UgZlOQbIHRE zhhHM|b37Xs^~`<52V}xG_?`h&^NT@WWCFI-?A(5KhZ{{v`Hb;F;0%GFF>xS#L|0Fp zz_=STqV7qbwko^)$ZN5uo(z&uQw2Z&(!b-~(P&>Gd;u5q85#xir}(9C5}}A8tO5?J z7tR7uMt*PU_4RT2O@^vX{>q8{!qLX3yZULA1u;jIde=(R?!3*>6oE`|jT9SLm#jb1 z(c*{`jas4JWc`J7G&jeqnJChHoj6gUW=3_l#Gykd4uW-{j z-X&f2P*+>mrF%kG4+D2PI^r&zR@LDRcRal4m~~LkiW9zI%&P9$E6s4cD?~d3V;f?B zu<`I{EHh5zr`3&yXwPueJ?z6`U+e#Sgy`Wk^@+(!V}=XTkud5dzxXOP)GF#K{0LsM zRAZ0S{_I#ag^ib}sHP>Ot{}LaBksgrhj^%wVjy8=)hha1_2|zZUcwA!y>BYy?^mwi zt-r<8A6@x!(iyLucK6|ES@L<`sVDjXTVYpln8s?Vv7s^=l*2`TD*qxU$VAZd=&TlI zw@OP@@h9!)(+`JT(Xn_bwDU*N>(LM8j1K1r${=3R6)9#%E-33$tgGcnVmYTUY^FPn_0z4uQfl4rGzvg~ouE7{yT$%poD5qfH9_{L zK0i1ZjGb4gsH-azNe$g9b(tC`zPfg%9b}Ox1ZIohh{>D1;er#W{^ovv$S+NAH6}6R zJB0B$iFW-8|Dp_u3d)G}=c- zAk_R@)c5uV-@fzt|2sC|m{rK46JbBoBh=cZd(qYmVb;1ig^m(#JXVDK|J7t)2SpxN z_}0%|I^h;RhVBj*+gpbV^HUn4rDi9<$cC2GpLgNdV)<3%Jt0E@Q$tfm;HOx-7yYjE$IS^W_#J zPq!y41iwoHnH0F)l3nYv)1J{iJtK{-4nX*PmTYg)< zSZvOSAmVY}nN0G&n{u*YvWXw9P!>rL*@xwV$o$(faN66~!%EUeC9TZN0y83*UOnAR z*7mc)xZ4K&Nr;AigT7r^VaIei_DWF3U}i~b%kalwREc6_if8!>5wO3YP=g32W)W00 zc~9lx-O2ho*K_|CE~NM0u1r^JNgXX%$+U2jSWW+>%iwqEACsc(8^43aU;15%rWGrM z$BuY%)n?{B8lPr0_W>VaJdxGajCi?zh4Jz*u5F?FZlh^PjZ*Cu9qNHam zlH4sLRpuxxO2@)YpeU(3g>n;K!qD2FoLvxNkg2nP=t#!kM@PmTJ5@IK?_n_Ot!HIe z+Jq`%iaServ<`c}zSD>M9Ou3^tyScaf6FzhySn;u`}ciZpOB>ZiBb)%%t8apzHsB7 zEv_`0SW}h7G@Jaf_peL9+B0`^VXvepggfi~3656pbG?kz0rssbFmIcCvn}KxHZdMy zQtj-R@TeRZ8b(CqB2gz6;HThkAI_sNh|%2W;Quo}3{NRyGM7Yku{2izWFfd*<4>IM zmB0ou%H`7CpQ;G^VlL@Eu>-D-%=#th#u`1GTgk)YWMrFMhJ++7nwyqPd(jCzxKH)? zZfp`8e>nCMaq$ULSZ#LT=54-im1LDWzFP5HkQO*l^Fn7p>`mC&o1&Ve0Km{zj>kfi z6#w`tgW=Q_S=BA!@2WC^kVI~oc^wrjp3>1~Bm0#vIz)icGA|RGJxIfbgKsnbaQ?+d zUsRSIo4*Ge7mRkjC4F@^%wZE~n6P|R@$Quh*ZsEaHfNuDzG+U~ACMVuk0E#pw@kzAwe4WY4_73kG77P%C(_T-7E zWM}g;sOSJmfX3p*^Ip9g-OK$vSO?91)yu`=A{inh8Xf~P0vS(Z_seAsrjfPv31pQT zb+u%%8(+!6M-omfS~(L4yA^cm;IEs^n*$H;3{SZK5{SIarDp%RXc&Tajdg1moT6o7Q+iX?;M6&^tWkAWhvfxz*-hHXpuB?RdlKi> zWpv(oF1?huHc+Y~`uqD4FTW4yP|HUz?0P1c4xgXDTlAa{l;FPWJ_rHt{~uFt+16&) zh27pYC{idI+}+)!#jQ95cP;J?#ogWA-GfsgI0Sbo?iyTop7+@AKK7UE7bI)0IoCPI zSiH>WtqdRVir&QVm{HSjUvB4FMZ@#dpH46AtEj#%^3}oczsI|NE|Ua?A;e<6TfM=S zhh^0)Ni)_c9N94b=nqSc6*U$82`C^yL^N#(a~wsK9f3?xv+v*@;To1T=;hPP=PPDP z`}4tG^I;T**NkJw$ZMw&2xQwst^6S?n2$5{KDBLH29h#Kcs!G@;*`;BE1&(um?S4> zXy~At)Kl~WD5sa=u2;C@p+rmP!c;C@Utnz+o+_*4ft6%Nt10Ews0_Xzc}Y+bchn;b zR@-iiTD@^SmY>~^wpi7O8A2#||F8lypfRaZ&x0Yibm9gSzp z%gXZVs{Ry=BTv@|utA;5luv$p!zv0GkCoZkqpXQz85{{ z|6fiuE=7}VGBGn0dF>6r%>ZN;AoO`KTBdWgdrIIWwxP1$(Sy|##qEu=Wsg7W9Vqn< z#w3-C4~>4CXeg&b!%SD}Z`oeUfTqyuOs+z#MbCu-cP;OTYs%5qI=ps`Z7BQp@q6TyCJd!AnJz!&totD2HKy7Oza}blLrqD1*qyYv zt;F&DTNqcSOVqqrT{#yYV|yni5Zx5`!RuOD-#yxwt|m{VPhX5^wKuZM<2>lim<@K! zPdu(Uaw=oDK^W;Hw^Jre0%5x$AlDPk2BV*Dj2izesapHzw}}W_$*Y4mDb8=9k_0 zw(F~k1{Apl;i^ntb)?H+FVk-Y6SNV4m(A(!vVBJPFYK;IQZStHc`*2g&YSF(zrbV; zN;TODy#tfeA2C#vx+|$|_?=C`88$k8-^X00;emasI*BemX`^8CWgWzkEo*x!fXG~y zN5aquyw<+=6Q^sAC~N)Iz`zW)EWOt_jCaKC0C?StDGz?IUjL@TjylaO%Im;267jaTR2p~FelwAX4JSOZ*TZfw!76iY!(70 zpWtvZwYO%w05y8PJnbG^ly{#|H_wrA*dh!Iso0(8K7*BQAC}_B^#lTOBR7l(``mCj zJ+S+Sei_~rX(HnY#OV1*vYWkp+`th^Vf^{b<9?&YZBalx{QLoAnLm>Yv+{(SXh^;ommA5W_p7|rA}#8jb< zHXEEn;Nc6qJy6Q7644^(k2vt{P=6_T5V@9YPQ zvkHs3(ojm?KS<2ZkWqS+m5Fe< z)InF_EwYk%q@>RfP%1sZ3YH1cy(Vc86OW4I0r?|x3$0h1 zlE39vo1SD$oGyWq1Alga*;kjE1^-OESuKHllY0^OyjRWqvd*%WI?eb$SfPBcd%_n= z>xtIvZ)JD6^jz?{B+N|l6Q6prTk5_eSzS0a9vjWB((edlgjJ8@p3K7MZc_VMl!Y3N zLXepheNe{AizG?1)6tumG5yoI5G_KxOouQ7U znXLe){c)qWK930HjSf3vI8+}|0xy~xrx`r+zPc;q3-+uH-&f1!qGl0Sj`G!@lG_YA zZ1;&{t~{s8mWbZdv$M$34giX)NSTWxczOeY9?8n|6c)!O_Rs7PoMduETnp-5o1G1I zxnMRNdq!G**q3Wz)*LNm--m)5_F%@5gP&rEu{%y6!koU_e>lP89fS#Faih1TYl&P#g7J*U{sjaenilt+(a{V+k5zUVv5Ig4nLX}(SQ_N?H_H!-+L=(_TLW9i>KcGcJ4^fy)V>+-8%7-R3(I8V2N z%PQrrS>kF+x|TYhKMJo)Z5c@k2@4PJ8E(t^b|#O4>%56f-}>sGEp-$awxZlGHZB4z zi!c0rf%y+hp8rhtB7*C&Qn0C9*8zEi?G5S`ERp^1rQ z2Vo{m1S?wpOdW#!^~mxqFdU?Ycd*BeELU>_gBM0ezd2z5gU1`2oWV=ucq&M4aueA{ z8%{LT%mOqE zUgMCEPa6b{u;a2DQvEOH53Z)(=>9a2<~iF6!Iu$>AjP2}ryIP3JM_s5rRSo198N#OH@T4LApQ--j!%ahK;5w+*TlIF^e z#ZFLV;418XQM;Hz0oBo|O!Oaip>GVjzqvI!4I>@T6pGhO9AdK?WigY(C1pVeNYZCz z5Ab37&{Y4~>wGxVdiDB&fJ=g9uEg!8fC|0_Db#k$5eViS?NG6spMI3M2i)QdhHDy| zv6&tcl%V=0;*w)Gnyh#ktr1uh9gxN>7zuo{R05uAmJnXrTlAjNVvoj>Uc-~~3hQZW zNjoaMO_5bYe=EPd$H(24!-(gaN-zllu>U=2IPrlop8Bda!Gjj3J8JEdv> zD^R&%W@pN>33ER+EQ3?o7=%povyq*9uu27v6fa{M?Dhi5+Peg zaYF%HfoPFtQ=l~7#QHs5;aE;5zhnBd4V}HVj3t7Munb9z5V2w`+2PLlSZ=P((!x1sUC@BWS)Q8A^f0bzO2$ut^ys3l9p+?huET$dIo-q;wjlwX;e07;*yVmcW(%U6)g z&;c|USbpQbToCq5nQ55mL`xARs>Pc~EB4v^K1I}GP-j%_0V_tEIvFa+BvZrqn2CQm zDn~H1!g@M%%$}S3aQ!8VeojO)7r}LxCi679PxOfHr-&0>7t$SlV_zz{0gJfvWz&H&1 zM#k;M{nE44TQcuo_2x|Y!K%gH`GWKg{@mf z>Qx(fef#!zrCH9++0+Qp%`Pu+P5fQmm|OlRNzZ(>tSntL)tUW4 zH=41ozP^8{j6Ua_C@p>UJLsPNJcz=ckw=tth-e^;FQ_8vI+qd{)?SV|b7|;K%gE1T zY_ToVSfV@7c^1-T%6!8=nkJUBq~Y<;VDpWtSlJN3u?LVcc-YhQo1&$OJrb4m*SY=BrV=;E_#-hp(bwDwM54 zs+le?zj}2+%!Wnn@z5OKb$bk_4!2f4xm=Fu`obaF5j?7x+<{?3Gf7- z!H!#iyC~_grwe{mtAg7TDo#{oq=r=t(Syf5Hnbm?9s@p$urryL7Ixl}L5qqrDWC)d z>q(#_$LL3Q5c}`LAN#)uhfbx*(}j&cH&UY-FC?M4w=EmlnU~)bhn8ww_$}ML<-mM? z6w967yU#ko*Nk^u+;&tEzF9)9c#$OxW`B2i<%k7y9uxOj{Q8Xcqx~YeOS}6Yej1nQ zZ-za&$XQgGOJ{~~aZFo9x|n}@Ipt@!DLRCn3);81DKbQwy2HFGizyy#IeNcF--XdR z(P-Y~-GAjs8Hr8O!F@A$s5Yx6@g7@XYyT39`P^1Nhw%)6TeEEcryDw9u3ljw+Vn>F%qVWlj2I03n!Ts z*YspL=pyDcF;5(6hasZHBL!tNnaYfvRbizh?5Til?*lXiPhR-=glDPn%2Kt`yxAgU zrIaD4V|2oc$lxXYRFP5*?GIocrAlHS^IrOP^Zi%a0R1tO?I;FSTsNHg!2mVXobUrR z#1G}N$bfqhc|AOY45MpD438XrIdxYKEG#}c$08R4PA6ATHxQYtd@Hi!#;iV;=V9|g#5Ux+5Gu0!5&(Q?eu#xAAtoD~XHlh}G(WR7sTjm)Y3m22+eou3Gck(dzkd z2ClQ>QibwO#5UYG&4p?=>p)j!uc!Kz3tvdPfX>t`FDffY4vjb?A% z=Dj?S8?++YdKD*+CO%=R@_!)XnTi1wnuUa$gwYyR7TCQmw2`qgmDw1wfK~P8j^K~q zV{kSad$>IDiP?_3WFl=e$uiNw&8=9n_Wb5}HqrOf(@Z50RRV=DpjNTK3*-^*3oUB3 zBhLTKT@tVNDQX30N~adB`Zi-)B2To@6;X*~2S=vw*oCl&r21T=E`JjrnaxC4I%&_*mzBREM|E?wrs0u^7iQG?kdir3{5#|2Y%C8O& z%p3^|Pb>g&sS~jC!qBMPXpc%)3L-qB9#+jiy?3~J(+Bn<3DG^PW4j$#=u_w%OJ{*+Wtn>@_lnf%=?3SOT!d|R2v%Uk4DC4(QV0% zM%m_umcJl+ue`onC;*sYj7fEfmz4?_*vN~YFtRZl%j3zLVO&5M>KC*7ubjnSv0DIN z{^0Hm^U%$rmVm#-rm%M@52+;udsHAP1y-aJN7E=mih^@g2a4V()_*6igFy7J8M`=a08So$<+yy!uu>@U_OYYF$$y-5x(+e(h zS;kYZdlD7}>wQCn9sWI(RR2f*$2!+k^2R?Ww(@$nVpsc~d-2Z2#{6`2E6i$^BSG`n zj;trR_#NXhD6f~$q-bAJRWVAQ<_)X(3nms-e0+|Kv=a8-7p$c6Mv#jkmTmUSSLrd5 zUzOrORSjJ|y^;ha)dUYbhdB!jsaX0Q4{5x%kuBA|pN{8ncXrV~feEsj`C8$oRL0vQ z2NY;D>!hY#5iZ+iYAK-Fu&N59>sg}9b&XHs!YHJ|=LqdGoZ=NHa=&c`R$Kc=f`Jik38##hU3J@!}QwBih# z&O2RAh87ThF-hA0Vac0ZOqrEy{^##0GuRDJPj#1GnxP?5tS8d9rhI&p?EVxP4{zdM z_)Rk-noqiJOoc%B_8J?V>N^nv!5f}xTY6Gb5>2|5elkG00(~a~{clP12~4waDXYf2 zLV%TVD&WYjoV*mLX6gZZ%AR1R5}G467c}=(EryMivQ%wwm>ub8s zo%tv&+lM;Y6N>G@BjYVI+hdUa(0St8-ADy>`#n$zPev^y{YF@b!K^B$8a` zR8m?CHY*{uAbq&b)ICsJ+tdUEUNXP#_I&;mObZG&k}>N{8lh{kMcO^F>o(pgVZ1qB zCsxV-?$!QChb@b*{zPB2*8NA&TDKX&Fa6T!R^sCVe4S;qyWc+{%KX8*=vA!L&3<_C zbuJszol%$1HJbtN2UeI?y=uADs$qZrHwyY^U>6-4npxm2L-uPBl8D%rU5xwM{`i%0 z15T1(ma?}ix*1n*qlSlXnJ&e>a4@RK?IP#qd=;tZygS12;_M7I;$Ig}XS1rRtcIt` zp0J$H^ZaGsoOlHiz!aJ8&~_`1HO z7xMP#tpSN`Z#4c^u^5;l3WJc27n=CUSVs_DqUh&JOzzc_zq~qLDPv#*X&FkV?R|D8 zfe59BB|VgwgSj(B*aKxL!sugLCTvxuW2&a{!ypy5%z_p>x#SIh1|0$maz}>IZ|jf_ zi@=|&t`U_jp^^$H1cLqZ@CZ8JAUnHV6!L4*>N?Vp;IQ_AWc%ZAiUtmXj@+N-2SOZ2 z1`!?R#MX?07K@$q>ihF1sELr-nnLO)-E7N^@&DM3x%rwnhsFoGGwK?Wa1qv* z8eD{}xKH;+vo)p_mJ7P)Z97Vd%OCF~8bnUBJ<~>77k3`dWypkeWKD-}ZkJYLzMDRV z3E5-1xc03rAt12>ss`G*FixiDW@H?=FXlU#g|mA`+Ng117|;G-15RL$i31f+U|}lx zBMgoqIVo{9AM75S_i}Ab@f;(ZFPgc~WVbH!*NUuGb_hiyGn3Y~aArnQ>!DM95H`@3 z=16B$Iac^~%w4P`n%>s3lH4Mn?Kyh;bbF%GYO9NP$XOHv(gW5K?U!JurKN?LPq4DF z4y?_5R#7qjpc4E!;d6GZo15qDslvVOt9#+QRQv6*>^+gs(X2Vk>(e)2&9l3U${mXW zD!^NJtsc{9ATO|cyTr!GAR^u$*T)l8`QP5Ge$~WJ=L=pj-X~Z5GJ;pn&ip*DSfNq= zY%xDiUiWRwlkn#JZ!IPAqn#|=4G+vFIjSOiD+#PpSSJG9z%20F!QpO+##0P|Kw5Aj zHH+N~tOVeWjkETr37ZBa5cKPw;*YjFy8v?@6|8PA{kG;~&#gfpnby4b8Wna?PuE$$YAS{~`3ufBtg1)Bn~(c|!5V zu6e)d2Yh|ql-LIcZ&GoQokK{WMJI;&T)J7MGzkA8LXpZCyuzszBGtWfvvWi=E$PIA zACrY|=gP@okm#{(I5PWK8_OlgX;oO6>QsYzyvanDFX9_T9*b8Zy0=5M>v9`0(AL*Kn#3>m|BAnUAYEX(?bj{$duuQl2E#&WETHe&i z6LD!1EVDeB$9Ql^%Xk}_d^uHaXMleBaEy3nN%4azcE&XU9b4cdCzR47`DkEQQYq_0 z56x$j6~CicVSHZkqohq8f14o$Z$kQ~rd`sWebIG)dt zd^TX{zBp-c8)xdHc99Q%kgGhgqvVa7gJ;#Dq!eRVfihH?^vnN=D6#43S$g2YBED*# z0?g1^586hW%7)=&2b}pf7>~A~D&o4p+u36#m|wJhX$)v7jg&k2U)PcKn8Kd~0ELAL ziR3t^8hSa{kF@L^{QpB5HmZ91#E%eKpVy(*H@j!#EFxDfoC^_&$Kn5XSXxs z$agqbcpFp5*e`6!3?|NrlOLK*K zUA8V38)SI_8(@XM*Vw6mo>pVaR+IA$<~ooO9!3Twj3;8p&hXW~`pa%B;2D*k%&5zkX>4;I z5}yCfY*2kkYjw-QMwXe`PRHgHcg>AOPtS+<;r2_nAT*6}bM4<4ef;Na_a9RuL!V!6 z;$Bk=5uSL10=dzb{1`KAhH8wqk40f&)Ch2LV{>T2T(4pexf3@?T_%#eJ;(3tFL99>)6iV|V0-ie#% znFZDr2*3uzj8GU#VgICZ+S`XR=apJCxuK`~``F|KF`dJQTmGhEV{Pf(<^q+D1!s%d z1lQ_}*l{Z^useQXVFZ6h0Fc|dJiw6n!Mi9lKa;$weaih z_o~|~x5u1uzCIya2dk0}(y0j4S%g&%EU7iiy7lNzV5v=<*O-t)H?Dm1d;fx(ZlmbC z{#Cc{LcX7_E{{vUx9fHLV1c}D`)0=!NM{JEvo2k31}FNkA}6tz(s<~cV0`QrY$L%p zZj+ofq~!K7;{URA!0j&PyZC|W+=c>9643@*MOSk8tVzMMB`l`nG@W~~blV>3FWbaF z_ebIo6QYvEa!Om9$}mS;3mMf*LT=&=0lTq+uC6ebZ^$G20h`YY!(eRMW$IGi9f<#F zrhgTgwK2jG{NskhBT@M0i9|AE{@nQp%?+q{Kf=2)H}pz6Jyky(3DbS zl#>wOv67}Hmc9NCHHz%#Fy2XtCal|;%8Q`+CaeKWiNwl@5;o4nh6Kk^=q$qediLGx zr?$c|ih~iEc8>G$f?{?DtoOOqBe%TG0#QsXAPEN6uDNh&9Y<(Eff%f zw##7akg2n@*Wuo2-;iwS)>1vICn4T!<;AK1l5cQHL6D9v59%WGKuI%E^f4Ev$hm#X zIulI%feZx5+L{tP;_mGNlI)Grh(d@3g9yGM7abTnj7YMF zbTt2k{4Av6K)YYM)gP}p6p^AKWp{^#1wAj{It1;H$`n=&B|SVGD!zw2Iq-=O0>&xc zMoHmTI3#P+iLlqzG3FGSET<9Jkeo<}&f`c2p;+LyX$mYXQNt{pSnCK?yaZKR@3~*G zX4_rWr*PMQ0fMZ}&v8plIxwVJaqHvz(1!jH(53iw^MUr9^!)t%Gozw~r6m$$O|hbz zTjtC*lS`@M8lx0?06!_|`N1w|2xIqE+pF|UaCYl)WApLXMY_j1wV$`1xp{6^s*cr} z&%)Dgdrd5TV~$^L(+~5t!ojP=_Mo#`v4o{c4BhkZw-1~B4R)2Zzc~#Ao~Wb?6!6D> zTQuctKRawc6B#d;V75$GJit6g156`>aXrCaf`#eO88MLrANz}=kw5WHBkFsGb5dK2 z_I;`!lU;TCy_bA9%US#Xu+DMMhkO|87|Mv|4+~dMgp+j_s42* z*a_)ZX@N6L$26WsU~aU!xV=a~z4O+`^ncoX`UZbX8FJrg$M${tX4;6ykVMLf!kr&Z z?0Z{+w}oq6pCM$F^};?KytA!=F^pv?sggisqa102}5!^ z)EfDU_hSUXQ!MU zu%!O>Ki_%@0VRvHVj6x80@(c>?0`c8RBY@4IYTgNt(d zEcz;=A%CZBoo`;TIA0Zfqke_X(eQ0X7o3owLF9;JZqItNEpV;82V%@u^ z?T=lH-c}|f;K6g2wtFpU;y^q0>hXNX+xLeak|E9QqZyKla3`Z`5$<`VCA+@^ybsL|2U7;8t!(RVJt$(pXW z5OAGU8ua@Ua1rngPO88OZ92!trd}AGbXOAasESBEp&&fbxNl>I=hX{*fx#f3(>4sWdP8i~@oVh9T1L$8 z-cMrlmLyg_o#Fsy3-tUND~~r(6e@9jnbv{pvni!%AW3#y*iZg;?(qsF*SqSB!tky5jqez~Qsku!GD0s9MZ9D84un$#?c>QrY9srYXtrv2bXBLwIeG_45^C;mvH z#MucCj+i3wz;zDB4&7juGuPb+QHyK?9M@KUyw%6z&aj63ntx{D>Wv8PRQfDDepk6? zFm8NS#eXQcPZpxh4f62B_FbQOD8O7Mmoa8C9m%r|niLcX7V|u;Rf_A*E~uz%;#&LH zZlP}(jaXP7RhfG~MC(8cmLPAZhoDy;j)%pv(WvSb7C3%Ey>U-N9S9iDV;-<(DEv`A zV8jn^YFdSZ9=oVb-8Q2L_xl@mziSB+|Bd&Q&r3|ltgFwu+=Ay6FHUIUyVJJD{ zjCJ5yFi!4GWg>vY1P33FD>=$kF>z~tl3Q@_MF5JY4Ch3Uk57`SV)6q6h0n=T5=_y} zbX}+gRW^ziG)Bw6AUI#Qskpu`(%076mwXaJt2Js`ZF4-r^~NFuom2~q&ZnAQ)C9aV zQ_xT~t{3Ff`F%t6x-;6Xv}#kT+!=ogrnq&@KX9_LXbJZ`g{!G#%41Kjm)Xsklqcol zecyDM_@W-|O8Rf(pj`duc`z{!8Ur>#H?d=T0haa#+xba(uhp71Cib3^Rmgr{qxCaW zVsxq_jUv!~ztqy5mgwKu3q})%jd4*Ry`3pmL8TBlQV)eE=mGk+MGspnFfmIL-a!Ed z{wB9`I}bLR@lH}z(Ra>TeEz~_;(?;!Y=P+ZW8HdKDwPG&irB`frN0FCTt)LXT9&;}ljXj>mDUXsVuHT~;CyB?+G9mQuT++M7R9 z$$8AT_$R=?bZ$ROVlT&G42l3u%TWh;fZwYU5vi&`Kibq|k4L?|*Lz2=KHF=`{EHUZTWwSVA?KjdR$OzAbY>D zfQO9)=7liP;9BVuw6Fh@yPowx=^Af@d5N&>(;M`3#Vx$QREF2NLF#UhKQ0@xF|LE# zgXYPW?$-IEo9b1EH4`P<;5CQ5YSSYix&zVSjxe-f=LcW=nk*1fPD2nfc3j>usk7C) zH%8E%GBlWY;Ng2^&g0?!9S2v`z&V4!G1EtSBAj09j+mb0L=Km~ao$9CrrznD*7wbW z-ilJ$eL2;;i!zh={-D7K>Y;AUOE09*@EZz~v;&rWQs&{A8jtN!h|hVzv87P^uZaDd z!f_9AG~Umi=m5N*CSoj3W&*PEH7U8M`z%*y#R3lt)SWkAh4B~rFNhG#{WteC#&j@j zV{124Kc?|rl@ii(Pg%1es@eAP-`Ju_o%J4C_v`sbBmg07(yUPbF2##~uV-{|C35wu z=eyz^)xTVPDqNAT66>Yp+@2}#6M8j~!p>IT0u`fmO06wbu@lC0yFoiS%W;+on#J`;QQzZ&ZwRNApGwe8?+O|!~*8{we}at9yP3Xop%TouAKoL?%n5cLcyNY>Po zcEnYiM=rT{Cfwo{zr^YF-XD25o(ov6zxH?2dv`pODfyGSw}GZw&4D@uUQ?}h0MFaw zpvcNk8$z}Z&tJwO>aQHorJ44fj2d2G#V=(ynckyD=78Vjm<+=c-IpBN?tDZg)ZrK^ zGTO0#%ME1q_IWi;n3|v0j0$Bww-tJDm)&al>v&jm^CAOPqe3;Nm=5hYBcIXeK3dTY%%x*ufo@DhG+0FI#_BLiLiG#3 z7Xwvjn8DvfDFictFp*@V%_wHrbm;v|qMOh!wuegojS!@p`IZd(tXv&zxpKX;Uo8%- zy?=Xqc#HQHE}D7~yF%%5+)G-L%te3JM`&H8--H8BI-K<#aj_{>CmKndOeX>IYnzo5 zJ7Q>U&pX>&F%#87Wz5BTY#5aERCp`b#!Aa=DZEuj9TL$`f7@nzedrNFy&efiv<5S? z_S&HLBw^am8kuW~P`aFe@{{)K~X!5f`sE zB(w@h#BCS}0;>nf8^PIes;Fs)FaZ^wr1ZBpyZ+qmi>DJ*FmL=F7mA6}(w8^>MbCK~ zOyJeY{kFq4+-ly)-}$L~Y_`0bEuU`kr|HUQ(y*8rQ5%W`#=IF;E3!ls9N{hXMj!97 z(4CGgg%`Ksi_Kg6Db$`xCUy8EDn5Pu{LG>@7G;7FrY#vaRwSV_!uA6EFA2`|Hvd2Gp24r(C76W{$E!8nzt z+3%$HVSGtjyt!Ls&2CRUS_adEY)A_nUBY0^`6cQq%wVR)F=|D*yS*0h3470I{5jyQ z2KD+{#V|_KD`jxUZflP(-3QCmh`HZOeax$#5$HnKXaeDQC_=Nw1MV}C-`GH6=v+?SqGZYS~aM(h(#5L>K$ zD$NF;R!o~cQ@#&eW4Q)mxzM1KAl6#XGqUR{qh|W!%WOB#FG2qqbt%Jrub}p!`X11C zmE;eJl!1`*XfkyMAqBmuf+~PYPfZBEn)>LJfqG<{x9qrdbx20WyW1{>H8m7g`dpiK zh(k+LG49u#P$L1pgB^BEJ6)|QjV4<_?}xuSniR%weP60{x+3=IfprFdKf<7$6kf;D zyBnj$V;bErDk)6aV>4jlQH_?vPbo~EsisI9h9jM=yAwU1Ey-!;sTpyKjYni_qj5k! z9dBx3F){^`KC;yUmRv8Lnw+&pUO2HKcBk# zQkQP}``2xiercJgznc^O{5v`xMn>NukgvPN=~v?*?i4qwiCzDoznyPORs@h?IBb&un?3&g^cYq`E#%am4Es5hh>Y%)}J^7?A=zU>jOMvRQ% zVy6(Mz0$&9lU>~9MBU!&+SWS8R|+qA9izPx!Kw|1uwt0V#QL6B{gjtJ(VhN2$N09J zzDg)zUuKtVF(M z6&5FAWRfMH+0@@vOlhvDV&RTzlG1dG{uhF^R2nw~|tlNs}aYNp@@CXY%$CC~6;&CgDGIAfy7I44N6<{&@b2`suyDh~F z(AAJS+!UyMN0DlSFTPwdC-zG)C-R9hC(50e`deO9BF<_8x*>{ACLcTRa>LmfTptrf zMKxaw;!o!>4Rd#$ahJ==6xt`cdPC<5i;nB}*dqwo7R;jII`Uh4X)Po?d)N%@p*nuE zyBxZQ2>;p-?{fQ_?6iF^o}X9Io}`|c;#vQ*m5Y1&_vrRdcxt^R6^XWr4Ez?ntH3AL zt%!J&6yK4KZTS3mF3_~rufp#Cw3o5ro?upU!9CUNwD7=wF|Jfj|LQ-2mV#IMB_9&e z)yhL6kQDwAu_t%Z5oYvXd?)4z5u^mRX#&N%+LO1>pdQ8{8vos@PEC-8rKafS71YGT zoLgGeK-RfTljN1P=5QVfZ&_P4PSXP-%9R}#6y0tS!o|AE3XSixnWVy%CdI2%gc@|Q z@pdgL%XtSkdEG^w-KesnA1L_u!brn0NK}&o1A* z-=VEh$mhMMiHkoo$K(!(#F)EedsAPIA)1HjXas=2-IBt z<9e~~>=HvU`=86^K*86iG$Y#28Y*Lq9WlD>7bN!Awl}}3`xXo+vMbf|I^$#)e%pq# z4t~7Nu)9=qZ@kvx<^DEATN^UN9J+(k^CvQuPHEl-&E{n2<_7&(4roypsy@cK;rDK8 zM&+^}V~h9^oOMKnt<8RqTc+m!l<7|+0(A6NquXliF1k!z21V-(we2b0v_tvnT-1*l zv~gz1<4~Q(Xsjx})Vp_Hn>dze$BlNC#U~XwmLR@kx%;;&YZRUX2I#UtvcQhy%=@ z_-GE(J447*Wb^2@q2-?tkS-z$3y|)6no~w2(D77L6<6r;TXNb*tvIsW(E#_jCNwAY zi>iv`$2_my%rn)EzkQ>ycG(5W~cuUxcn%nf|T(Q#nGdn3Fr!=>Jt**{W6t~h~ky`>!r`Gtu zT@M~mD_U|Ur6Iv!V7CcKII1pd6?Py-kGtFuSGHQhGYd)nHwR=qvf$?6tF7lqO^yr6 z6sD!#A>x{Zep_I*-e_O3tOgyLhb%U`-Cu8PX6yqP_403kc$G#=MzJh*o%^%^HdETz z_7^|2hd3~F(|D`&g2nGV6PZ{@2m8M`t`&3&bcLs+uU+q-*_i3r&`P^EZcdM7;DbN8 z(L9B1!c$)@N7fJ$9?edCDb=&35F1KN!eQomObC_5r=_KZ#ZbomKF72AvpIYx`Uk%B zB^}2DK-k$6-1n~H1$aFu>;wd|ar*}^-x@C*)e$q--QuH8(NT!n2H!;62!!;;{l~rU z%yo8tw219u)pOJ5uH$;Jah>w_$BfIK^0|gbKi6LNw-{lrOXeTG*7f3G3KIR;@)WkK zUF$!Q?cNH6bZ=Kg z0P}d3)?H_w@w7>99TWI>02%c1E#CUipefeow~OiH`i;4Q zrE>)1^~2lv@JX9pO9OKK419UgMRe$eqsrl7qqXOF&m>Tpv zUGDAn?`viQ)Q|G=`e9FuNSJ6c(Fsw8$OApSRj4a17d7Q_Cx@(iHJ$k&4GO)XWaB^v zgzE9!o|7I-K(Fow#>S9<0LbQuzzDs$9^-Kc6bkln- zw@#MeUY1`1O$_E81MM2z=g(UQ2ls9!de%{8JB#ghrQ<+vUPzQmCM777Jt3w=r#lfi-%NJR=%``hQi33=G4>r)H+Xm5pVoRpzWh= z%E(&^@LQ_eg}$9cvD=v4fl9#+4y(m~fr&fr_PgKDiCwAhzu~}yrn6yC7-wzE$ofgR z7X&Zq1nH6%5GWT`G2bB1Im3Z_fp^~riw~k>p%3oNf}yMq=#A701^V6;uL*@XEF>wu zsbpg;O8VaM;NRzEV>UVobodC-$xv)U za!B(3-X>ay>@JeuY1e8dg)v$yq3=P$-F|PHY!?wr^apz{GW(od%k^_fMye?)#ehtg zJ=o>d^Kz{QeNIB~_DNug{Y&t(36mAm^)Ca|H9&U$538T1ti9}lX=X%;C-d_ua6IG>MEaH;ONylln)7CF^6iypC`KmGodWq%9}q*+dntw{SJ_E zVsFYSw7+Hl?CN%~O3%A{cx>7SDFV*qRTOQndfDSQ^aR z*sdJcR6gHDI>M-Nu#T_UmyU7ox5dvz&u+XMu3gL@@5#q$?>R+;UmePn7*Cp^w14-X zQ0{0YF2qm73944IbCyiL&f7Z`RVMPn0(#TcmN)r=%GCfxb#m<^Z`rP|wb{i(AaQZQ zW|e@UC92p=QHaFAj29vAF}!w={Ixc5{$UimdNK`7N)Jc?;moCRFCs6*+?%S%p?8Y) zOsmLd`0IWh%Lr6Rkw|0UMqM5M?Zl9J7vP_)=pHtjl-BN(05vM3JXTS$X$-&Fs_wpO z4do(@G}~gvWyv&@0J3lzBYsZvVRs^ZSlEouD z>Y2y(h89&$s9O9eh5lW%FW|Nj?DC>XPBI7?wGEA!qw(>57j9)!kcarU(t+1GqMja?`(6b+H-G^(ehej074i(Cy*wdVNO@o zyP1bK7XHC#iWl`O_@_s4Dvk<1$AfMWCt8;V#-I*-<1!oj--53hwYtO90vu+&ZDb=a zDiaDjwQq+w%RZs#z4>n`!?Mx@GIHI&R=jPfGD}}l@?_O7_FH0->pcWB8Is5PE(Oib z7_xRQ*~}#u>%k-C_Qc+?TB=WZtnHbGH_Vz6JN} zq}S%PC!OU!*{MVh|1uBp=RiOw0N@lo13$@jXT_isQ#!Pu`R>n8yw|W0(h^ru9+Hzi zkZem(&28~)^Td~tzIfGqW6lA6;=Xcjl9Nk)LMP`O2mcz=7xUmFDH&lsWGjvN_VVQqYWhI! zfWF&fw1!h%1Mp*#oGo9$c7e&Zj~h!2agv&?fKKPE37Dn{SgSk7{?G(CZ@=4*^gl97 z_suqQ{0v-k-8*3r#J+Oe8+>3~b=s+l<`TNsny-)VF(8VEQEB*8Mw=cU4 z*T$LIjRjoM&M;#5DC;RdE3XJRI4Dl^ej)Pq-khGoMGyV5?1i|#!u1I~>6>o4kJ*O8 zpR_bhhvtU0qa%h*F5|JT9&90I2Xabg9$I%57k<|DiEfE7&hDC-*QH)H-oyvS+I4ra zZdR}PUnerMJCKfn&vB|bAcXIJccvmloA_W}&^i>I&8*X-H=3}sdtWq##T8CzqGQ9C z>frI3=h>Z%6%a6eXPPpc#^d)PCd>^@@vtw957BYAojnA&dr;Ql&gMDX#n0(VFx4m2 z9cg8feA&&NKiV3z5F^-LB1vjIEJ`6I2c(j~5x1_^Q2rx!_j0_`_TQWQO7av}@_70` z_c7TWy;i!Lp*g>i6pKp2aSdz{XJVNgG@E-jlD!Em@h8(V{pRlds#DJ;p_J}6q5>)3 zs3)-dI<5~X-`F3$=3tHd&)?`?sOku1EC+qkr&pLSJoVsj7U|d?Xd9fjwRrr~va%tw zkw)A%z5)Lp*kmFSS&C#otY!#CO`@+lf#0d-FY`F@nde))2fQ7!18f)u`Iox0CNX!poWx4&y%nxaD8uj}=u_@6_ zAFN{vs$Dnh6Lb+Xwi&KxJXIIcp!Eb$7MnsXCLA&MhK;uv{hqdS;rt@0I3m0Py1$|k zIF(mcAn){ZzG9&eVf3zHnabt8DC-^SL(0?)Vg-@!XT?zJyS(m@4mV|-u>KK0VDncj zEgd(o*S05#)L{=HDRbBSbo)$XaOBl_-qf_Ou7-N7B?CE0jjF1 zEJ^&XCMQ!k2?*zBPEGb(c>KE`veA$Rw}wf#axJK!CEH``7Zn1C#WD~$X-5G>^-CSr z{TMupQ|2Rx;t)*Fd}Q^vVgJ(%HlgQ$j?C3kjOPL!9Rt2k`nPA|;UPZREa+!7alrTG z$Maz%RGe)sxk2MmKg^I*U!B4!0wqq3sa(2`R9`vu%!QpSLfYIlryaTzHM&1YGf;W* zH1^7B`adORGH2xMc?tCXQTgn0WxBz9pIkh%%wEWnO3%7bL_4A_VM-1EvDaU*_T~%r zE*I7mMe_O5m?16S$aW^RQ|O`P4RK-aL$AVYG)Zt@EY;UE`RsvA7ERW4X4ELl86N)a zY0$#%P^H#EkhDzWQxJ-g;!ZYO;)L!MYmV+eO{b<$uyq`&MgAMV8>~=fVC&NLboxU= z`{=XhdQmja417M44yr-3q#UGpKDF`xxRd2xC$(7T_Gk-XZX$wG`P1E3UxI3FT21dS zwta4TwAIV?dN$s!W;K>b^oiw0`{ckDozcM_8?B~0*+hniKjJ8}RUREOjxFhCC`nZ= zSz<>cCf5fuY*y4WWS)Ui-TGod2|tC@S8P|ygFB_uGguoXQtKMQy@XYI{Lpk+Lc z=gE@#`2N9*U5v?X@X%t^RGyIk($|K8;MBipH~1v^1q&==t4a>-e1Wn8#XJx(4hVjv zTfniNVB|K0oXtN^d3ui8m|E!W+zlABRSj|bWvAxgo0(=5uANn4PF9C+w>TgwCRA}1 z$7ZD5zvZNTYl8H&=H`9&h}w?Y!W`xU@8A{MN9@=GUeGb{IWr2+96g%z)^@&1#X3|F zjnc%4m6f%M1tF|$Y)IU$KujS_W@D93(dk_Au04Rwvw^qWZNTESl1)higAYy5=(5bj z<39Mm_^JEfw$J5j?^;AZoTDJcU1q^Q_F*0*{ct(^hG`Pws9D2&DaQK9Ry@$O++FV- zzTm4rR<XUs7{vq%0)}%9)YXCe(&fk0_qU6$f%f2doid*MaQ=VQswr}43UK5pFmg{wVIeaeB zm-O#eXo_-it!bTCw3{is&J3IRZ~nc=2|3R#GJw2q7@YL6PD{1l(pCYW9+tFp{`z^} z{a_WiRJ(8R_5mgKC$YD<6vFbSJbdAMI)A=Y^xn}EkXL#!J73EF`4^Y)@~~E7+U!2r zn$c^&uPt;LySAZ~)7V}v#YQHTTeHUS?$O0IN0Tn4k(r55tO z@;<`~E*E;}Qe8C`SZN|_G@{3io5NRhe{`%D?Cn0YQ%Up}kE}l;1%BEq`7uEiHWmZf zNP1!@0#7ZI+DW(gGkCDc5lXv1c>H%^2}uX z)o`MLHc$?}K;i`WJ&a;7qM*p$fe0oG__n27e~HS#{v*Sor-_$pQb50={0=JK-eF3xD#T2xK0O5+jLeL-G31ug#Yuxsve+M@%9jCYEF^*@`v2+B6IA z1lnmUJ*HL*jd$7Iy_%v7-Lvq@54kLxs-mpW?D_pC#q8_^_ShC)lPEu&Ed3r`6f?R; zrE_49=zwN-{_G77bZ}16w0wNz``)z5P2wvU2KhMWbh0R32KyfQ_@BZ_%L!-fc(t~9 z$z#&ORR1p*m%a~xQp$l_33>Rf?|ZU!j859umekOy!`_v72YirVp)aOk8d*=erC!V1 z3+UAAXzx$DEBc$z6#qeW*8q?|mvL0cqExoh8|dqOF(@c7$7swuKk9r(MY=4>_@fv% zSWSOBXMl_*y{EHO5|7#9xt+@y(jmDnAxRr5bIUEL@0H%EZ3%sfv_jUc0@z) z9kCmzer2x#dH$z5E}qATEJDJwD(V zesy_|vcqJ&@JFpg_YS`pN17bppu*!^8;4n&sv_M?HnGZf-#C#uWvr^_()9c@umyAw ze-L+YcPM^Dx^!7Cq1|Gs^2&~YMkJ?cN)*Qmq@=v125`oaiH5{ea<-jMC{=01ijhd6 z=vYnA1HHQ6xHE5xqcrg2)~}v`=SeA`Oy?ZgyG*85I2R&|oZV9J=zh>}(S=jG(nxska-_U?-st zI(EftZuq}GI<2^h<%qXCV+ zyP-*gJEJc97TAX~=i34Y1Ln?Wle7KJ2vKTWkq;Z^E-_@&7Vn_h{*O#4cRtOQOFYPSFIBd1EVlUkonB3oL+47ZIOtBIQ5vx~j z)&!K_eyw~7OU;}tUhruNAEAB?@8(nQo-HA-GsUUkpvYvDEFYL}I;0$pHo7`Kkq`5x zbbJr=xH<1zr9kG|{i0PPg4uRw!*7l~ z|I0igS#{FZMY<~V%8=r|FMyj6Lmk<>9#_@)AWp}`kz8S8H%@ahF%#>6n>53bRXk(N zzF?`UO~auM1kt6UTC`{9Ddc6{s|)1u63)14EBVnTU6&fx|5T?(viOm~8Ms&^;b{4{ zU-$iDu`W27CxW|-Hd_ukpw`ro!$8u;Mpz{$KZG~6m|?lFxt9t=qwxkW@U2wC@6eP4 zUbC4?KhLO#34a`^t*uEk$SP`0HlH{F6gRB6r6AYFrOoOrvmH^c=I2$_{UJLkeJnxUrJ-jQW4=WXccrW8tV4LzvTZ_OxK66n)+tO>^-$aRV1!%CLt6a|z>z1R z%SmYp@nR<|h~s>4)*@~gT>cT*@kcFEF+)K*PbpHi3-w^=yVb1r1hV%M7`5{RbWEMYv&hnbvi=XLL66Xup|@)?&<-2FP*_mQDe4sj($p`$}aD; zw|0z6$WhP{7KiE8lt!n`+|T#8hxFJG9q&z?E0{c^xHo~3=Jpbxj zQf}R$nW>mVQ?4HASX}i<4;HOGQP*qE+JkDQ$uN>_38R@}3f0YNm8e!oH9;s_rW1Cp z{!NHYKw#}uapV~lBz@VBb9v}dZQ170YA^Y}J04$!zGTud)2S$L_L#rDr`S{uk)Q`G zTu|@dfM?I=S`Aa|C92D$syh%>iQWUe4V6O+dQ!FJIWi8DHeh!`r^fQVEY27Ro;8v2 zJ}fUn$gn3I`+{7Fye)UxGd>BTnpt!H!dO1jhIO9RkqZdBp#)&ykVuQj5IiHG#Uu4M zBx@>TZJJ)m$|S)4Y?v%{2InpNJ8rZtf$w9!aWYBcAjLWvNZ-Sr9uP361tQN#jKti~ zyW5KSvPL^v&O0Bsw$!U%_pqZgpny#e>^{Z)ew<9nszIqSn)UHYHZ&q;&_J`DzB;rS`aE@=-NsP%GpkP%k3DqF_;|0;36TsK9qt>qF3~Th>h-s7 zYKZBjJhfbYMN}xfH?k32y3t_qUyyiVbLWX$SGsHT>JQHs)?bHf4*7zcEcRF9GlVHy zA&D~H=ft=Vo&vE+K-tNuknXJ+keF?VZRvIiL5@`FBW-I6%Tx!8|)^(!d;(Vm| zYhIJ+A!LK}ix@K^7wb;onNt*Co*w+A?ZxAw_S@ov%|mJ=hr52Bb4sPp(lB-9GBB5~<3JT&hzrBmX*V9i=db>K;seGgRzPTO*gcbH zV}8EWsw5UR2K~c2%PocpAq4~`wqU}^$r@1Dpou@}*wVlZU`^Z$!n;>d zE&_jpRp$!Il0EtPy=Mc`&^`Ss(ir$gb7Onjyzz?7m!vj&p zv#pvWPoL##{)fMJ_8Th0$=sk&K%~Xw5i~M`6;e3`VDa2>A@9MH%5~7u@4-7Kc`1)w z`k&~| z$u8S?Hj(W0vxaI=OV)$<as!#3@?_k({8zUJ0J0v{}tjd6b0duO_wlmh8Ys%J?qp z9OBwJQ%d9SQ=l@X@qJht63mkn+=wwnX--l z)cGUNyr^vuDy<`*kwp+uhgrQ41{0pwEbc6UwwuN#=rZnIaa1{#N~nZrA#-70%W_U0 zvS;f7uDnW1Al7WwW|e5PeVMAQV(fH>l$hUjB8!oVWT4iVZWzzj?D}g>Wg*#31degQ zR40zwI^Kf{C-EzwwNfi9dh>cng&Iexdd1$LsnKT>c^IB`-ku2tr#BU#8jmXwY_9UX zUM%yF5ofwd=D-?-WoG${^IxRuT7ptW^qRbl2C?}Hu!NE;m>n?)mih*8f*!EWrS%Z0 zOyqKmf3wxsG8j=);goMW{Hc!^!i#*li@78K1`QGv1re9jcKY?QdFs;^53_UC8O~Zm zZQ_sAs8NbFQFo!=)q#RI#!y(e@Z9f_+=7ASA9hj6lGp&HP|LuPKMR(^#n_33BL%fj zys3x0s&mL445VN#nc>i=!_h1l}{b0CgM8vmIOx|LnuZ1d^A=t0rE+BeW-xfNAs z(rO%hPtnj(_!C`y|V{X+QURKmMxerG-6;UL=LAZ)=Pzj8Rjzbav z{<{0lzx2YFn-7S9w_;FIQgVXX?SiCa3BQG|ivs|lMBd2m3cp-2Dp2xQSr@0|`5zHc zWm|c-p%*W<-IPG_`nRu^J&Lj6Qe5WsT%YM7JuQ3RK*N82uoGb6;Lxgjjb$pgflSmoxO3(6;6XV##QK%%^v8!kIiEgO@u{XxDy3F?Vu*InVA!1p6U?3pj=IqXX_!$P-E%ntMc?j1_zntYq^4FtMsiW=?jZ{yn4f9`@7tFfAgIkm|J{v&dxtk_fvP{Owqc6p?SCfLGE*E~CAvec>Q69fmFcyc~^%dRU8{+F!sTmWoKe-ep zjPxZu#p`$6>YyyNDEjzQ#>n?wcHi>Y4z|#=4#geU3v3d+`K*lQ;$-0-B-a;mxLyRj zv33q(oGoZGv(a1s>6waDXC{v+3rf0E7{J)0KGn0dI~yg0l}a_?H14{QVReGsB5h=k0>kBuI0GBP#g&_od{ z6{%=h;~%enViLiFuZFQ-ov0>I_jwXO(O3o2VePlstLEK;u6%AuxqmEUQNLn!HrDeg zDdW|9!?~j?Y_^h#HhBO3@tPG$!uw}E5Fsv|h!HEJ-W%`=`a*&w<5W}w#YsC(HYLeC zCyG(@jFar;?*f7JH{+zo&i8V0J#8;!haq=F-vPtsletJvVaM|+6nH$F953y0+XZUfe~v=$Ckdx##dSB=my`y*j92Ra)V{HJPc`^m+I#tt zy4nspZ>5D9ZEb=X%aPrNF~)c^NyS0RbZL{n^V)D~rK++gh7tm}!}9F=7ZcDcOGbi} zEgOzG!8f;%{|E~r^Bve$f}$Dt!~k7 zKJ`;YE3z{G4G{fqpEc2onuaN=1|OWt&x+d}+}SP9NH@`{V_5@E(AY7y=9e-7 zffEn2(GEGR8O@FSIXDm|giL@Ho^f~u zJ2f!%$kOOTS6+gHOV(5r*2A83EIT?z+{&qTi82ag&Ex$_i@dH1z#KZC>b(GM_**iMtbwNd!#H8T6g50{@pG&__%>WQg$B zfaobGX2oJ8Jn!l3dY2(ZD2Z8}*`lL>w8Cegpep|O0Q<7%T(|Yfhjl2?r{BUx&}{o6 zMyqL$`ARmLf{i?q4-q|1)GKeQC2KI6 zpvNte_2n;m>J$%;?w z12tO}Q?=c#G@5KDj`y1~*{*hDu21o73LiQOop+Y$i9V8XBPll?1IoBrBvoB&(x!b! zo_FC6h4o!y=p>0QarGfvNZoU@O?F#;8!Myy)jY+zYsG^WMr7Tq>wkO>UaVhgJ zO15x3H~vnwJp}s1uhHaso*&44GT9MlpOL=zhKzvxOLsilRESUTXJ%3YAa;p%ErzwU zueFg~Qo`MZU~EyeqKADWZ($r(U*wlr(SHTEF{#;ppt`oEjmhws#WFEvZsIJj@L0%U zVdqV^JSPbY3&R}yfqbrnl-o^>MSw|ZkeLVoT8G_S**qfthI>QGLx_R=31R$Dg?(Rg zBy~#a-1W&Wu+%9H`EpmI`x#5`XISXOM@i)6k-#nq=i9#+RqlV6^M&|hUaev~{Zyvn zw{A6cT`-;V1-h_623wWq%oiIJr|11axXB#nW+Z7>yv~5uP716{^MiyGxm3Xbr0QOl z_45fi$R!K9qDL&E#GCSV8)=kV5h~W&EAuLKR~+U4UkdZ}-<{2dLg(=ck3Y&eB;f)S z?(V2Cy8rf1Tu?biv@J2eGCDacMm*mxysg;K;;de@87~U1&vWBk38E=zzNKI%SKu9C zLs@=aOQfzmk~J_>RJL?7C@(L%SI5<|)($RlD?>vK6r)G34woDCiV6a!Rv9N`GpK+N zL`6|&wFO4h3F~ASUA_3+GE%e`0!JcevL%blW2FH)8Ok>j%`29mf$sy&vgA9I8%3km zS&gmlYg-d|BQTEKN_eRND&RfYGMakK+R3mEU4XZbmaX+Lpj2)nxz@{88>Cw=wxK0Y z_r6x{Nm?ve%utF%3v-$S!9^RWN?S0%boA4qKneLDyL7HDwt6jcR1>muDR7Y&#SNBt z=vHj$T)O8Ryi5wN5~;~cNGnCH(nxn%*0sQSo)LkCdqw05rqPEkr4qWliH1s{aq4=( zd;T2P*{hfnv2gmK6xA%}GdU+fQm!Et)H3gF2%)09v*4xrv|TC(3oa7ASuD z1hX2@hQ33o2EIhJu2vXY!o>25LJo?MjVvg%Yf*D5k(!TjP_HLhYQx&1*edCR-*|Ru zR<>o?m2b`2wd|G-O8Qj2S}NgM~kf%Iw z{egDy9~stHRg84%;!R(t_e%)=4KX{d7i+fX3@YWiwhUt-A72Z8x$F*p8zR z>WpkO5O~8dYN4M&`jJuj(Evx-fOgD8HqLP~V!J>Ukv97^QnQL%+}fH ztcG~N4OzHw0dKI@GKF{n;dPX%RRW$ZN1;m}i&oi`hf1WL3Kce(j@1n?oJi+6syXwD z{{jElRR6zc*zM^)w$sGyg8mJe3?1ke3mT*gM-jT0x|!5zS~HntFzDa7C#^8=@kwNi z=f4v)-tT;ChgtJgXLw9z7SfS1wTwMVp{CMH8U%4ZB1yk;MGW|(O@2^+NH|E4f`x^# zAfO$M{eEx7Ce1==#|`^xf9Dq7TcE>U8TS#Gz&Sd=T4ga#I`mkLk(o;4t(*tQU0?i1 zJg0Et;d0Ym9f8aA=Bruh`8X!%=hJv&agdbna@yXyUixH+cU;*{2nw5h-K$cBht zZ?ts^`-n$r6aq4PbI^6JY`!_@)VoixdTa$!y8=|Gj(Agt7EjSDABsP=Tz9w!!98wn z9y3ueaVqQA+#W0hKb{bd?oGI}x^;?nUlX>kdG}UYo$}0{Hd2}>n!ndUgY2dqFFeJ2 zLdwyI%x6XeiH6lKFA7#!-S3%QjtRqxWetq8yBu9z0qpF$qvCtV#0(FDUnC_RI8PdW zc)4No#U!3jo$zy#GVXf#Q5ZP1QF;@W4bf~j2U6Jz=39t1Va~02C$m4Iwgi&@I(O;m z`-f|Q?*Akpiu5byTRUU)ms?Zv76goAfrQF2{*lq@?2#1QyOVbDR-xFT9V~1%zftQ; zmf?on?a*V3Z5A_!*8pxFvGqepShESc{t2yzcklW>Mo6{FC*cm!b6mS$C`5EvsjEb- z{fa3(KGmoEOVLSZL+d_nnTh--$Y#uMoFHuF?v|J>x3)8e{XOO(}1UxI(Fva~$D8MfB~LP6+Eu%6|;{of|_ zkRW)tffcOD9R^k{+tyqnXUs}!P9s{RO3Gg9u#toW3Pt1s*WBV{lXy0VawaAxG`@Pl z7493Cp2l)^#O`O{fKyphY}l`f)n7bgS^hsh`6-`>8UXvT+|FXYasL>U$EEjvGpD;v zUd|?pmLF>lJ38uHt0>E4|7bZf18g_R%18rfdB6!TAMw~dl8;|OzY}qX?RQNgfwakT{h{hEB zqEa^X&1Zu&%-BvVrOPk&wsuo^j#&slOp1b@gF z`)8Xh3j7y)d}UsLs~f^E#c^?E+;cVO(XEs7Mhm~%n&X`GfRU6|eTGSpb1MWMBgmr? zT!dd*;XHao9Khuv&?;)<;6wx?M9d!@(py2*oU-!&G!f*;jn9`L5D=nH&qBp`;HOn_ zjVACd>)0nu*}_a5GkcN-E;8f4`M97_mNKW|?uOvg}=b zTU1ig4Yelt>WR0#ahDlcU(I@|AXh5A@q_n2P2|UT;R6fkTDqCEK~72L0kB*dwKrDmgNt z^@yrkqSIv}u=B!cVnx@oHEdCzF7&63{XPqn-fXNJ;LS?l`yCs6JgR1 zo)IUousR%hhL&MOtuPW>xkv#Bi;3ZvP5K?-j%!_>nwjkHKu7!BJOl!cZ{ecMt#desg(@jfyDy-zpE1Ykv~P1C zb4Qr8R@5xzj$}@9Ux>u?2;xt|=qcMTmn9;@jKw(BP_bb``s+pORBieR+Mbr`nn6>` z!0RTtI!?~Q?sOX*|2ZW!ZJ_$wkL9B(7o}x?R1a*BoUh8tQiwE(ORhJpFY0Ek+BGXx z?vc-lbAmzCbH7}W+j8L4q}n9g-8+R{mo^>J6cey41V0~BWw)xkSfkY2AB@j#MR>aC zK_Xu5|CgO$SM=gf9OqO#Zsb-TE(PZ(W(sxivR|V)d@;_5#mMCS8)@RbK}q`9F8$8= zc9Hng)wOl2ezn}q^y5Rs%xB{1d@+1NVruVTDU_k^t);npi){b4_f-XPTV}UubUV`n zDjuf2a{2Npbew&PYei?&RkvS0G!?|-@uY|C!5M?HrH^07cDo-P$by>&O!bA9y_+^C zW{At*I?=DrI#r0g-7eebCNjs={reJ$5f>cK@Y38!&HG*$+>QneA73`#5X1qnzOt%E zkN3@0mkXXp1bpAitLQh`nq#)BshfWj>v*0CvOMzgNEYFkWK z+hN|m82kkv?>p`^g|BA^PnjP3U1Oi3TR~^vgg!j;BR!}M%rbKmwYAf9c7cFzt>Iar z28K&zvPb-}eZ2yW*`+eAD}E^@EfTE@DMLxk&hvgEeTknL4W8p8a&|M8FWWagJc0*I z#lotYvqoRUxI@3Jf0Ygr{TzoT-OY>kZN-xX1o2NCt2;8axS^_Yo<8E!@2%^K=aypK zw*bE}Hv&$%AiX^{-$v~}o?Q`%#jgHra!2l%W5nLocf9kYTt6lWh!CaecrS{C)R@$M zrc|=(3SqvRHm!7wIs(zSuQO zCCNWTRZJMx@n<~_$o0y}b}qIFpQUTaIRy_ix}VT!+0`$O4*$)h2ogj7VGN z^dB?i5#wS4=(q4a3>h^j@BMo9vvNY?f%?b0XNVn0`zDDoP_m8X6rfZ>vaT*8)<^Fs zPZaR`X#%{JLw~)lVK}|;)4CfdAGHZt?D``P=vN_TZ84_IXZ95cc3~-79w$?KZUs<# zx^z|#r(CrVdGT2sTn+4ySWM&Tm)y&Zggg1}d0nc78$V&L1F& zos@WvNqhdEag6u51J&h06d*;n0m`0j#h%S!$}&P9TtAwqtmTBt4zFu#`*-4P1Q`Xs zAe9`a+W%-R2c91-F>JUqGO&wpNoT4&g`B{(>P1ef20k>45h0f4{m_YST%p{xs8;{# zG*r0LG%}6zV9h#d$kbt2*lAe(Q%f(PtVz?yq1~L#q^53CmwEepaohku5N=xL4~90? zK`LD;0Rgm>!44(VmQ_VX2X&hxd2rIx;^zmD|8TEm#XznWOkX}jZQ7>V2o;yzW3FxSTgJGIye0y{Lv;*!61f;15rVacjdp}IxT%mvL_{;ix<$k|I0 zljGnZtSC-!(yx`FN}!XqEYX;u-( z3oF5~sm1$gjcT{v*F?8)`17LV`$8Ve2wjPK=~0HI(jm*7jMIlR%f9!q+;~nF6 z8`@ZP1og%$WYi_6xq4~8Atf3a@l;Wr_8hAR#4;=+zW(_~a{v+}w|4a!HmAQ?^hzCZ z(^iu>a5023c3WbYX^*f&LMckO$3Jnp5;MvK5~2i|5+v7MLisbT*LWCeFl=={Xh$KCV-d6l9TZ&hk~hfBzlr6N=G z=Br#RHyPDC*;55|XKdM)(Nrs3RX^k>69Vkn!*)w*5_E7_4a9|N!De_x9LDywdK6JH zVmF*iQEg*m{?v;DE&n~O$9I=xQ~{*yccZIFuz-)<5-dz1XKU}&ne@6B^CGl(Pbm^d zUSriFUOU5sNvnK1Bz@{^StA5r!e;1ksy$w)TW)8U#3XxJzS$Y-aHr4T$)?>e&D>jv z$k>u%;0*kI|K^4{85<{aXSExYGZ(smiy8Gv-?eBHF$hK{38zWNHp=ae{H9f-gj^jJ zj@oFK;t$9MWdkFlV?|M5#QfX3mcqWzrhn+V2i|%(%ix;sDqT99{FWQHP2e<|Gj<@>ckkk-B13d(b$+0DN) z*1uar?Ci>WvbH)}jvLsK4_&C^5MBGU>RX=@h*+I+{Uq6NS1>szfKPp^noij{WI@yV z;=Z}Tnan8Ztl8v;xJo);9-%2!vf}o~J;`qS8D3~}CrPFuQ|PVYp>w1!bj)A3FZFcp zaw_DX9ONu0{nVy+SOcHyL~9Zu#-u+ir2+1<>EncP>%0?0k9x-Gq>XVu??|Aim-+1d z!_9u5>=+YeKRrnS$%#k9c&`uh*iwJ6M==EO%pm?UXSVAt!MVvjcPN=y`3;ORBNjnB~%FrU6}d3o6N@LmB%OuggRMOfQpeJ3>bzQH|)ter>w z8<9`}O{dQZ<+u%;?_>Vi20i_D#fIGiyieO9->LXCGd&qnd2A*Z=S zdnrf7po!LNV`AvzuD!1#=3dDj!^0u7_q?>JeoX_Hi0z9=4(2DM7z!3K<@%`ZRiX5E z0qyT-yE#9To*HUpXe!5oS1^?Oi^X=NU*Tec_pvS*u}Ox~@EwFvSH zlRjk_C)%fI3r#2X90UMsk$?6Nwj4xsLyuHT9Upci%$EbLC&eIBS)0c{v??f zl#246(bT;{eI<{i7B^dxX2DB5Q@bn{y*d26CQTmY@)*hOM_QZ79NT1oe?sALw9wBO zCOixPucVWBm1;|!3x_gto3$_SG-5i+qIRz46>CCpwChV?r?<*E{?pFx`JysBVJNc zX=-MTptA#H{j*P9?8TooXa5D0d%|nyAVoBNj_L@z4r!>b6bIbe-UCb2{pVyV@dAEeM z7tupBuKUrMzG%@$Mjp43>cpaXe!aZ((kUfVg3K=*e7H( zFxRcJ)UpFPCZ=%g7t*1sx9z6V<9(*j9g~nxb^K|oc5jjm?s?Bao==@IyzCC6@k~_@ z!_yU3t7diL#H}C=PKaG&jj?fd7%ocp|Li$~Q5-&JEP@`7q7c6$EePb2e2SWXlme7# zH2WqBJdNjg+;qy-_s{o)Nk_>8aLc1 zZWrXk9bmZEpE$m3G1r8gRhMgI_}*wFMoTBpN6Tpo5_`mNicwCIsYAvk zqR4eQ5TD_4iY>4DlR=-PqXALuVqt7)zJV*vm2lG2bTUHBGjDxkHgT7Uh7w;f(~@YJ z{Or^5SoE+DC(+<`(npPX%0+Afo{-qT6L(E$JNqf57$-}a$-n*X`0l^#5&a0Gq3#rj zr@7TM=EnqH%1|v>yi+k38X6;X+uX$lCW*eA5Cn=z8CAnR0?}mh6x|Jc_%}RvuV;b~ zSL7>BKM{FTuPt+tpwChM`4@lYj@Bo+Ot^(3uDZs8nbV6!2L$w8bbEoY8iS$DxTX?S?_Wy`vq!C}SeD_Tf|no8EimrBacJGVr_`Vw+8%QpJ& zozODNclO{vrX(>C!E(39gJl#l=Qj3n6q4JLb6N$fHmcGJNbQ+Uf;>F2)=sYZQm8S^ zS>q3Ed~`;6t*`*WwX$MqA``-YvD`mh9V{aDjiPb89f+=y_@4c8>Js*m$*mV_mmX`% zJ)*<#GEy4oypawHif|XUBoY=@f`b$5U-87uP4~ovQq%T(d3vsIZi-u4o|ThT0G$Xa zyJboIKg1X4IT;J_P-ku#QDYn_xAvEXlW@DeA?-VZ^^vLHOFEWuq5aEn+}{*-(PWUW z9AMjL6qu@v!^owq!SH4S(sC9lXPT)U{56cHFqVpXOTw>toRC5WpGC3oT`l-;(PVc< z127lxrHv=s3`%d>0>#v2{!ltGbtJRrN2PR_Y(m!dfn(=)qGK$Q7fcY&V4k;n@5eak za4Kt@))cAn%~d5oK#(-$h6O~@QXe%O5oV#f@#RFiF=9IGy%=K6+nMMM3T@EY1|H6V zlH?uGaj|>xNM=-dF;{=Y@^o0mAh^n-q0-M42G%l#7U@#(%0@Lvii=*$UyQa&%aj9s z3cf4nFl~+Rp~1maf~0fEyv?{zKDOm{l;l>G#1g=e(&itFvd{n?D5Jc7vJcz z+TxXsS^&?Zq7N+ChQ-4Lm6b}E3whcm@nB6I!V&f*)j}EOu2QcWHSwFzECk#6ad?v9}m>6Qj52??b;2k9O}V#pa7I)`C^p$5)8 z&-1Yk&9NpM71z^IZKe9Gr!&#YN*{!<_NwS`96*)TqU1c|I9`*N*p}hjv8Q zR%`$SwI)*8h(D*lh#9ULs>+yGntUH@z#5wHvb~C|jX%%1O5c1$m+9821%GQ^*W84Y zG_bW+tYO);bOzfo?Kvm2F*tF5G8qP;!Q)bdDq42vq!_QOwk~`ut4;WrtU)LuV$r8* zUR{Jt{OScf3RbtPw2eq7$s)9SM#j}@^y~aXq21E2x`baWB4$QX{@Vb{9eDU;kfYgcl@O}n(U6uhX* zb<3WXn#IHVt1-??U$2t8#K5DZ?PpZi5e)+HOv^uFULV|H*VWGxEW|>Nec(JX<@`ac zQFQUM`*KR#IZdqLyS?C(0x&Kn(BNvK=7bK+yrfZ8jXE&Jv=?I9G^oF8$hvTZD@-xJT<6zK<-#hCI`m#)7kplyP@7c8v*Uwdt%TcIQiV)g_t^CGRg}MzuAH z*!v7t-xcPT-6rPX9$RfHPmAD9SB_Kq;HeQ~y)2ztN&NK5A}w7*_orlX+s)hW_Oooi zsUt=8t^{kUF@ZrmD~dKQ{l&7TxGQMOBYoo){N4YBnup6`LnI2$;@GhX=+qsJOvj3R zA3$#+U*Hnjj(vF`P*;P^b$T>;K1gw!obhtyOgqf>+;A7QNBs}b-1|V#fX94179P%> z_?mzrq_Sr-$J-Iz2$ZAMu_|F6VLr=2?VgWijt2T3`jn4AG)&geYQEM+i|rf0a+z!dom0|;zFOVhSlY~=gpxng43Xle=Z zuF-$JIdTtSUT#GmPak9v&#!-O9OZw+sAPBRmjCRn5;mW8%Y^hX#cq~CH~M2CWqOtD zw^sy13of7uQ(>~vJ@oI3Z?re41bDja<08* z1VkMy(-*vjW`6Delfe_K{KP7E!I>iS_F$Fid9hT%8GKvyGbP|_cfk0IBbeF;vGCF^ ztg{s*wQI$e+F(P&uWN&d(-VaTmsbyUPsIHJZ#dpkw?o3NJBNw4WvJv*BRVA5h_~gw z70E<;c@dP>M@sR6iUK;Y=DGpQkO!t=I_jAuhwP1Q>c||Ar(qBAf(N@h#0m9)T=js! zJ1o*P=>!ouy6xW@4ogKk<9r8pO@|H4+UcPSe>Qz+1bMl}dvrOpryD1OQY;(2VF^Vw zi92)>L0R+VZ?46=|5gS&U=Be2J^h)u`7>V;@jaF4L7*Y%~~sjV!|?Epi6k2M1v<$Zc5D0x_-xZ}$&cT7Zy{kmvVj{+C0O%lN54NPy(+ z<`#+a4~IB)&5zN_Q3X|eyjcth3?2TLe}0zH_L74xPL?RVS9RX3U}kD#8%7fKwtYjN z@}?3K6Kvl(Iz56bRf6!y=nJUCE(Ol<@%fK_ix+n0zjy>n3%N+o z_A_*>AqiO(NWs9ouUd>)h2)Vhg085G06q?jBi!!71_*RIVe-LeHzK*U)L>SD@w^QV4z>;$Phs`1~>?DEkWG>BJ}OE z3h%aKPDiaDQyg2s?zaKYIZvH3`@3w`ikFRZiaHU^`GqLM_i1feySrQ7 z%HFNN5}Z|xhl2{icYn-R@ftEsmhXNVa4)q;i%^rGr#pfUa{DTuXIKLgD1WL>gr7;o=VP%#4B2%z2Y=(1Dou*Rd90lCu8v$!6exC>~1oFS_ z%A~9qC~VXix^Ct7HF`pQb0YEo6IjE!3RsT`7rXVS&3qp9M z)fhK_X)T_{WSvuud!0GLZ_aFXr`?#&v$>7NzVEmgcZMV%$1?>UE9YaZV~>IG_I~tS zTx!ZDx?Og=B3MYiAqs*-U#*;&c-f(PDaC-A?Z}A!GV4or}EMX-!O^Ba}^U# ziyDn4WuX3O;*Dnoi5R+#Aw3~ye)X=Uosq+xH|Zc}=nz8>nn|g3U2e;w558*lTXk>q zfX-YMDlNBM^3ww7GJ4Pa8Gut)7f8&N=;OYk@oSs#UGlaQIh9+)DM@xaFnLG!b<&4}L z3(Ls3!@RG*wO;iT3y4d0zM>#bY3{~(Lab9m=7KA0j(ijJRvQ&4))SF0;H^c ztE}%V zXE-rHXR0LXJrOC{Bfm~0quqoW*9$yNmcM+&eC?jF!8>9YDet0TNkCV?i+rrD)8Zji zev@(g5eY33MYFplG0qIFxM#(8rktUm>!$3Q-_9vJ`WabzidW<^Z1uSkUMdQU(Ym~N z0g{2l^!r+IeQXx8MIFJ{8#{;bea*j*^Y*rO-|R(Y4mm%3pK`(P%^E{7-*je)`V>m} zm*$sd)FiAb)$~dEAG2qCNvEmV=AfizP*m0B#GOS5T2Z~q{@@uvizx{E(I1CMNl2J( z>EGAl@k)CH+wO z{;mEUigu{uZdBl=pF>(=hl3%|lR_&gIDK?fx}S+iYcCB~D8P0CgO({AnX1;yl?W8{ zVb$1*SDDMZ+$Wt1+vXS{U{p%*pou?ycCZ&pq@&4%IFj6ki{AY&X%Yp)gb7s22{qca z4?w#1nFF7Q_-kkA*|9^^?Y#&`?wfnQRlVLmP;kWK`4mbW345@t>eP)8dE~f71%C5b zm?q0l5DznSxZiUqn_DXlir`A9n$vR%|!B zn8iKs-;;FRon6n+ESGr5*Bt;3?vuHrPX)5AlDrbGmt)(kBy>~@X}E5^Le>K5B1WqR7RwDMcqkH>gaLJ zua)bdNQGeco$$TpZ>E#8#kaVt5`sR)topk&=Q$rX*4+eYhqQML+&%|>d0I>vy^fbq z-PMx9RzQ}tW~AsANbOO<9(Tw2EQ`WDd(Tr8DLfoRFE-Vx&9dUaQTD6zX>VI5MJt6% zVS3CjNl}fzvsM!tZ8A6!#b!eW<}>{`uLGmgJ$g@`&j|gfpDQs7!&gLMx9wUEa%1oR z7Wf;So1KW2^{K5zuvY9sefFEX)Tl-+!<|l?w-{m`@1^3^@9ksJt&t4q2W?xX2@bNx7yBF zC=hn(ylO4{X0hR09FasPwP4ti=tcxAunqqc*M80Qn$=S93F)Ze>n@*1oY4s*A<}>ckaRHwVe_xnFpUKFYwwf6XCcnVV9{=4^ z9)=NK%zSv9?-!g!Jgj;M1h3FxhUtP%#3%v&bJ<&^HNVy1ho8zS*)so?p-JKpNi5@H zG0LdV1JY#(Kr++Pa0G~XTD4I-(1TWfQuh^%<@hX~ zkh!gMFG{X9c`x~1a|fpujEr*8g^&Jsf1A*B7qqdn!8y1(OKRyLcVF-f;T1mw7RdbE z{z8B+L)`P2E?CRl4nB^F{#gtyCjE9*?_+NdUO#O;(Xp*Uq@}8&_=f#637HS7dSp06%XyqUZ>_vF>mzRuoa=EoIjS+o2Zr- zQu3ZJ;BN5j`ZE$g$qKS;Y?ABEWWwPirFg{@JCEJju>l>8e7E-+!xqTI9ha2}g27J| zYI3*I*@}7)swA}h0`1HmA}R}4?LFQR5fM#*qL%t}&ry27*qc^FJg!@mx5+Q{r-aJ1 z${(t#g!u8GuZy9ZjBiIQ-brGfBY&n>^+D15yoUhP)qvjD%I;hy_w$axF3C+8XId&y zTuK$M2N)p!d}DDArxJ7;aB)U)qF$;t%5ZUdEUz`rRG)z(BPsr`Isch?w|}Kir3LKH z0s~`Ms@Pr~eYs~*>I&eK2)TwARmyFMnJRxnzEG8TvJ=j#+zZnawK99r4 zVoxdgjhQH6xm8Ti?bDh&=%J4~JOt>00%25(@wOHj)9;K`B-TFZxwX%k6oR(v@K`@2Y{9b{Z#x5ZFo8pDbAJ>`_RCaN7dV3j(WL%kj3y-h`2 zP{KhbPi%~3m0dqa$I>U6DE&U~##qvrT5IdCmGCNZ(y47xuS{|nWQBKMEUr@B_>{o@ z)Ax{xmLT;7$}x;KJE6ROmYs{EOYo(~@Mj9Cr;wd8kgS<5+h`@G?g)}p7qdEftW4sA5-2%P0wzwd^|0JKS! zd=9B#zin0OqU%XtUp`~X%37#V7XH>oR+mlgxgPcmtuOP2{$)*vKdDW>e$h)_`&)?Q z@uG=y@)X)X4nrFE#0d;|YsRTBCN8iw6%qP@@>c$R>A{dJZz+*iDQfq1Zs-izrT}kU1eptgzR`$Dk#KME( z#9%`H&80zEO@o=azQ5`D$;`+9J0yGzVrKo2kxel(VOQMbzaS613HhnMTWishJIok9 zQOOuO(385? z5oB$9xW5WP)_+hoYA7I@nt2nY9m`MBTRLPfrS96s6n~b$3>r-20Hng2qq&xv{rGUM z>>6zhv87PIA!JH*OVM7duho18~Yl`c-aOzI+^VY0&!EMau;oB8*sTY(=ME9XzcfKus`5|7g zE{}_^GE}R@9x8Rawa)gHA1ZDUyb}ru2!3)fdM*+0D}8WJ|5(x-)Wu|Yee#l@P~{VsDB(& zW#UrM8Rse}vk~r#g_Dxw#R{FsF%`VAU)4z|7)#SPMHf6h%Zii7(dwaFLmY3hX2?TQ zFo#l?gEKND;gzrC*O*=qY1)P_V)++#OcaquV;mdyp||?WiKnCHdlCUA7fj8W#r_uC zqlGzn=ku6x*zM+C2J4^#KMnUYCPL8Pzk9`$%n)y}-4OfVrulgEs4k4)6Gxf!lMfNg9!k-z>`k9o-1 z<<;Qyc;2@!??|kz?F6;tX`NV#>N||`rqZS1%=I$yRT-kbv$L~(yDf=qnr~avN#YaI z&UaXdDJVV$I7T%9zEB-$-=optO7Gr%A&`@kYvjEg8612j#%D=gWD)lCf6(ibc;iK< z3;~^;2@i>l7lcC#DrRiQCvcJkLyzzRsqW2{1r1OMxK^RQj|mwB@GCdXDe^s;H+_JV zm|9BTc5E$9D$+@9tc~J&Xce!@>V+rwLB<{~1IJ~(>tynlNb^^&9n)cDw#uX4RPF?1ZA4nl!2=8D8%2WkFzopFUg$3N&b=;M=9dj6Q9zfbGk85!mS1|yoAe86a6xe?G1e5psyc#TKM>GS7bkP$pcbuY_1%y zlUx$QH`6VS)NMna`dC>eB$eHIPy59vM`h*+}u55P|{w&BWyVnGslyVxmUF;8JE~c zvLEz~1;jKYgg+H-tiRVxS~rWRTm0ho$hAhf{KQa4^YO=Mz||59=aI7=5l6o2yrpHb zifJ;)ND-;w=sHo!>A@h7Kt^HttVK-R&|+j9Nwm3ON3eHcM`e-pPQYJIkte6xV7bBY zz){%nhuER5-$u+o-&?MrCL;_&l!N@Fsx^LiKCaH7+ztR~H}g;{!Y!h%FMp=?eRU*a{Ms7?`z{#! zG%>m>32emAk)jF1=}WyUoVvFqoz`uQAyL15s?tJH`0|)W#p?QPi*V_5?QZh{XS%(Z zRiEy-n%CK1uD>or`rfp7#-dc|7KUYDibnRQU%?Ar%~zTGE?B?hb7yhvi+Mhhj8c_W zZB@^eQh3!EEK5k;uqIgW5FF^sgL(f7=;I~pXNZH9^*gDqgZL8}M62pP*ES#<#jZU* z*?=v|t#35C2*`JGX`->*t!B8`8gXi-Nex=^JFjV;LtgHX`+YjBKmR2~ApUyS&84W| zcbd<1xv$6Oa^%gnx$_&ylayRxs^1#(CYfZ#U8)Tk@iO`bI-`NdEZFwg14@-1e}B}I zZaG=G&~${>>{V>bbTnq`Fukc5<*`~dC?&hRma%)~^D~L7aw6U@8a?dydbgl%o8*^Y zY3R6y+3wSB2a8hpR;@Sh$LeD(~1;TNE=hS9p8OfR6U@`WfiJ>76^p>^gm~C;D!1Hj3kQPWxggu#UcWN8-5Q&Q- z#^3((?b$=+EFVu==F+G8;8>D>LSH}C8{OVu&+)P6eh3f8z77&}ANy=D zZT=_QZ*>`X!Y}8#G}G2wd2JU=fvHH%es^A?9&*#!^m|K9$hW2dOjsHy>beqcV9=7) z-~iOao4+VNwfuYTROTg- zBt;)e@;dgJ84OKKm^x%e1gT01}iv3eemC>o425mi}i`CK+^_WEXIYnx=egQLEQ z?{@*3P2bi`INeWiro=~|u0#8yJ<#Oh=l4NFeY)OXoBN97#+09qB}|mB#^sF_7iT65 z$Nuw>Xjz0#(-Kh{nyu3f2YQqa45*|~A~|?1rck0<(s@;?aXBj8(ARFK=4 zEs`!}O^q~}S!TF!{0|>L|1u8`$`I+uGZfy?jL?6Wqo^BXyA7Wq<65D#mlvXc0W(1u zrUi(3X*%Z4yT;$NrGJYH2Jqdo(|MjQ8G>@azZElRbB6J!4(NvBl%gC6+V5MqgIK@v%6h~P1U|m( z%MXrO$5eYjD&5F&-dwJTA7^u=`d%7BFHbs|=KB=P%iGPlYRW>x?UzZ*=L`e#5@3;~q zWApNA4UX?U6I@{Z`KnBCs`Zy3 zgyA$|6-hfwx&31fTDnmgKnD8FE+qUzMylvV?C8>ux{|t&T8f?NO~Y?|!#7@wn2@%1 z>HYPMsZIbTi5tbJ0OGyPxw2mB|KNHHU(jK{Re#&J7}EuNs(<^`9TFvpKVOAGVpjht z|EFyk`o*e9rsF8;i7L|e-}vpI%!P)@(0lzS6P;-7wbnxK;3xKF$wwcVE@SXoFfkSd zk*k5Sr2U;gOu?Wz=eqaxb7K=-3*XJeTVwbi5yuAP6BeOhwe~Z0ZOT*0PlG%f^mh1z z+Rvv;rv4@D+B00iTz8{5sm?Ds+zZjK`1Vu^s%Le6yAPQBR?^MsD8*$tMfBauW*~+40`&6tsj>pSHFw~Fo7>U@8{&n z%#+oj>?1(c;a~5Qqe49CYa5dS-8Y7HSpJ~x)pT%J=M5tOe zu8l*YQ2%{R2OwCHmB*h8jKw(vCf;&#Fl?prD8tg%r=L;mKQ2^qWN$7N68Xk6;d=+e z4jSYc@r__J-1Dkn&S=7xk{bECCFEQ_?sekJU}gSW;#a$FRo9p4wWLk8eOl+uxYjtI z8TlM>k?1Acx8w_cMFhZM1-Z7kBV^ueZIM&pT~!@>dE3wIf0XrGvJg!T4eFP$tRl&*OyC3`rv_?wH6VKV|511>Q&XYElieOYg8<7=9O!WIL5_7Xj9p*q2d3TwCO9utM z=>Q-{DpSdJ0e5!~`ukul*W3Y^C;V7VJM~ozHk$w|N7}f8UY=kLqYw@oa;b`#I}olw zcrp$9)9>TD9vTy>gj{M;qVtgB@ccf#I@27uiX{r~U?&YS^|$%9H@l%r-DrGWxipQ^tP5&X61Kw?XCeA0y8pCTV>3oOUY5s-y=W{%tWQ`V%k+6mOPM z{H;uV7G#o=OC@RLbePnbMsASppWsqO29=&R_Y!Nd8=MevUF(VHS&_UlZ1-+KW8a-? zX#-%QJ8oiQwcYYMNb(@(mCsdsagA+R=>h%PY9mfZWRc|!4!@irc_oYQ3KT|ZOcAER zTyl7+e&0;}QhI)IZRc3BR9-!mA`k{f>B-}`}qmy-=LtJYouKn(9Y5f!#rD-17z~mO2 z*P*O{R^6nEDR@XbrSlHe*%=I@+^CPkL?P<-_xFEP*F^_0x(&b8?Rv}gwQ8R)zB)U) zNmy5G_(#2f3C)P3%XfD7mY@~Z{i9sGB!RyoI{b^|J}lHnr^GzMjEnF4+DimAg&B?$ ztr*SkWuB4=)N^Ijf}VY>LUZq4>NhR_lBwZn6XD-4t28oDJ(8vu;kgj@dpr%hWf6QR zR{yqnbW(PaIyG=|vQxr5c6RPNy1I_#k;gx{OvtFTs#!pX@b}YCckwmcWsLuwL)*+$ z7QpF^ttMY;L?=+#Sz=8slHpJ>ZMW9pl|(I+fY=%pG>~T7ohj-+c1oMdBNxGh}bYI_IZHMly6M=lLoH=|hx%X$oxpP1To6W1mf}`~~5s3+%p>QS; zFJ?^{;qmujQ3EK^{xlUxy6kiQoy3QaWh_!4Tw>~Gb+kHcJfDGvG`9yuV%fvO+36!- z!1{!)>UT^VS%tXVz#np!kiZ)f5q&KI zNWqr~JRvEbcc<7P*xDG@3kgQ^7Kh#PT2gTTsor~)ZP^7%1#A6ldk742LcI=vuZCP1 z$eIESy)QFXL%ciF|4}|Yplygzv+NygU2!X4-lec(XUxn*rDC;%^aq!Z; zQ0_gfd2nCmki%KCXRs118BlrfA7vfg)?m70kH)=`&Vy*q=|J?!=6;-uK%fW58c^}3 zg8CxhPww8L>&`l@hfX+u67ajMZDIGsDE)#uVAf`TimooaDwme`$$;W{ zdIouWqG@sOXyLz{h5+F&j$V!R@&0b1=U9Zr62sH*2%=N(oh!T3wcFfOVCQ(F^1i?+ z{b@*OYJN`rHy|aA+?V>5jdvSF`)oaf3#O<57kbzZ%rs>Ix^a(` zFM6wrlg-dIvZKZ8g@SbVgx}MSI1Qxd!X*$8wh*sN1;U(=$#|0v@7f4c#`Rr#*$6E@ z4|-R?$5%86-_%+@FS;0Vue3P;OAB6*&c*_U zQi5&k@1N)$snOL0rE1kftqTn|%SSN7*1LDx4|4j8Ff+>3!T z<~y~C#cyJypUCvRZM>zS>=;)R$mXpLB|?Tl=X{T(p@pwb4iOA|t{o$nd|}&0|CILk z2S;vGZyq3QQ($xoWvb=&Rjef!Mbpdhho^%-X0DH8TBv$Q=J0nDb5LdXo+vfh#|K_$ zh`%1OS~n>)%;S@F5gs|`r+dWla#OKJqv>*MASLb*j4YG8?T94aH2=fe?evHGl|R4i zR9rPxt@Ny$nq*#kz9>3t-4lN# zPtmD#Uq3uIz8TGeDhp`w{%iopuR%5atwv|I8BVkXS5*bHO!n;PWEGtIIr^#pC4e%r zf(zEWQ-4&t#TMo@@5}kPCP`w6_R8KGVKCWu>SeJ@VMEG|KfHZV_AaWDKc_1tO#IUo zSa@tHMKXf7#XB+Oi9@RP8y`r*`gl$~zfr#DIMKUhJ&VeJu>wSOn8#^d*fLar*e_2KHRGzq zXUI*0bm7$rJZB;l>zhtnZ0B(AR2@gOb2xUZBjVfHNs(DhZiW(TzVT)Hl$qP4w?UFd z`TJJoB`GB_72=f)F)^X!lhTGtY>HFJtBYF+`y#UAHR%UV$a?BM5T8g3Van)1S4i*a z?X5i|?S!bPEvfHVHaRrm3S}AAB7J#Kw-(>nwXY>Y>N~8f<$C0-LOf$ej3n@#e)u>g zG%xrm>hn4zXdfl=uClU%r2Fsm3Q%t<_}#NwoR`}0l2m`9Es$#)(a~R&m5Ach(cL#} zXF+#}!l5dKg_~E8y@#Lho#XvF`a(^5t$gg@x3mj}%AHx$r#qkVwTSF0M8@pQ2QUO4 zrm$qAji3jDFwCL^_>lN%-IN>&k(b-9Mq$6uoITQa$hW9SHh;82b0ubfiNG)zH$r_nhPQ=!$9Q zgz@J1)=uzkDD|y3Asf5}IX-f5aYZ%Sgh+ARzxbi$VfYa)HM+yNacr(*uz55k3V)vp zd@ACzdm50_%=m}LUYXt6WT3(ZSz92SK#*UN zWor9d4Y|LBiqFa6h*>4WPSk?_DMWmxof5d!tcQudLh~37W%ga16SS_wyyYZEQI-}P z-bq5N5fVKBmHC@pEZLiVf_9Ivsr7pIxXb*t&_^a<09*8lPUH}yo|n6yTTn-;{hi-| z;~k5V0qCb?F~hZZ)hwUm8!ZzQEbp8`)3Uq&?)TG!%~lL>mT=@pWff9^)Ho+34WH8E zd|{pFy3~o*%13=4@gpx_{3xPsL3y{5%o~ZZlJ7}uRe&RlWEd3J{}oai*m@P!cj_3v z`{9q#-YIYXV|#ZO8*)F5<-XR@KRg4{kwhw}GeKd4^)o&i7yUW#UVO`t82~(NKon{! zt_b$Lr1e77EjD{03}K4TrWm5U{4FzheBP~v7B^dl4@*BYD#8(yJK8{-GM;UnbkDm= z4hL8UG!R`}&-t~;K;I$>?mhRUPS=3L3-$GXg24fM0}>C?*F5&_-9xQJ9-bj{^i$8E zTa)>KYZ&e9%uD|MT?N=76jlfrdJTD=&D2+U=$%3J44R0*&o9PKRO;`JN@}UA%_3TiXsJ~4;;{Lg3(1W>bH-cd;EH$_KtYJjTx+nZ2Oj8FsC6&7r z4m!a1yg||od44X~iG_{akqFho<7PTWyDdYerhOP2$DTpdfy0KSVPYK$E0Z~1FT2L4 z0eqf^6DmEmCq|7fOvQc3H#r~r!X6JsRoiw>huWbSl3=BLG#+`l^btha`sB!~#++vI zP^>iGm{jTb`v(%R#~T56+I-PtR$hCl+28GFE0agY&EBL(WnwlqC+|Lg{@iZ&P;?z| zvjyLaEN-V&xI-CoCzMZCbXH*PnvAS7AeG*3<=q6~Y&f4xd3tzMBp-}kl(?%iZcKc# zG~9i8WxM@MgYE9yJFjLp1K8dUS;FPh zPH9bx+3{j=MfXjW;Y-oIFJDb$Gmq1`q zRIjGowH&{qh~=YXDdS~!!~x;s3QvA0|_GDBby! zZCJu&Dc^WT&7&N#w1q2u%NATifF25teP;0Sit2#I#>!r^K9;e65Q61GuTY?o9A}EA ziKhi;=$rI!?*1k-u-yD?(VZ?VZy%E-aB)rp(lPRZc+6!xANDagf_X3h&)J<`(s=byHnE}3A$mthf>klxk4 zT&Nq_y6|Eu8Qs8tHS})`m&?YbhU`e%g?rkS{Qb;?L5Rnm(ss|@@^}B-sdN9PUz&RV zZV6d5Jao7rA5-%yjB>kHS3i5Wa^EWB z=*hgiXkmDWwJu6ZW#c*99@5Y}?J{%Uk(GET&t((p|NcGyvz=W@T%cfQR8lJYx~tnu z#r%sQkwsDRJrSLbaB~wG8W+w`b2UE?p#}b;P`kEjQu0*syygN}6o((fn_`wS#y~va=UV*M_ z^$mdru-IscB51D+QpA@fw{|#BrIsyA>qB}A5SPAxpwkrLhP3zQ$3wcuq@g=U2>7GJ zpxh8xix^pyFPchOF}*n)h#z2oN>@}Y7b`cDH@*EsK)pyf`|Jm9R1)pRis=+^Lq~#1HA)7UJdmJt6wT%eXt5ZwO)9`V=;V0yr4>|j%Mb}IR zb((!_>#{zlTL5yT`(5UB-}!p4RKfj)TbT4EM@V1{Qto~Xvupm7 z?81m#G{4>+#1HW~!E^8kodQGGbZhEucb70~DbQszTgStuifvqD@R~NP+njhfhb<=y}i@(P7T-{rqa@w$5c;f3n~^8zquL>LF`DC_U>IDX8<}LW;xt@cvgZ? zYNugAIYdBNkQig=5RO>+B>!5EPjr5cWXJt7J@Daz>vZkmo0bP~x^`9U`l4+=k*Ln+ zXb?4oFuaBxI`sH$Jp+CJ!9+%e+lgDuLgu~N1Enz`XD8t z31J!5-&-`hA3*xJVT`R z_}p+qL(a)_Jp9g<9T>e&B2zorc>b$5+iCWIMw=QA#e1BA3`^@z!$84|iCsWG-eI@? z>GqD>WolqReIeYVXLQff0v5{!MbwF-#%DCoFDXlzhDEwL4#OVM6hPw97R$%D8IREM zRX{3oAsT*jhBK?tZrT~Rg;xv>H9Y1cWvWV}g@@oW#%F|?vBiKiAdmYzvtV!l>J|$~ zYJSJW=(E$p{$O*B*%bT3^khlEXNPQzaiVcZNJuK5`@Geiq2Y~Dt?&)>QE48g>m6lmJO4=q1}lOmL)(F* z=<^$mu=`_~I`fBYK%d;3x^*{D_+mexxUh6{YVV)_HzHtgF}@(hkCuzOd-|atJ3V9- ze2|UXQHL8Hf}=zj!}W(uzk}Ghkh?2t$lWbPJMck1DG|^areap*BIg-BS#Ya<+=mn? z4!fqX4E2p^m+cvh1v#_P=7-SM9I@jSs~jOW$lfGD1-CMO-IEK8fzQoi1B|5sLwe~%e8 zW-N$5^Xaa zcVLN+if$!Uk<#O+I{wkJDICkWI>znvx=eY#@|cW8B!|7K>%*0fSKS)&g7%s!G`Q=t z&3l>DRW zp2T>8Ql(y8?RHkrmcfb5ux1ZzZj~=?7`D)zX%PA+EgeNAc0tXZgl*+S7T22AUDelX z-O7$7bKvaaZePZH)!_T$bqENvqvK&J(={vOoCUY;v40zv;;c{ix+aVL#mBWAW@is6 zjo~V1l+a9Rapng88B#(1&*BNXob{xR;d)7O!^t7?cd~#eMRtc&_x-Uwm(A|D*H5GM zz(7tf#A#|8n<9pi&IbOOySK3&2Q29*su)SgWvhMTSANENN^~IVX6IPiarOOhpDXu( z=APVbHdeCmZFN#v<)#AiEOX@3Nou#~Fx=7Litd!NtMJRdPPme?hWU zD#bW2_m>rjE^*ZN(O+c0_r5$>RWprmWvjip2tF!>s^Rn&ne1Qvldo*YHhGM)D~c`= z^4~35G7b3bb{N%0A9`6lFuagK z{YFQcST=I6%pP%QgCFR%8DbIU%F74J1KlsDapzJG4;<*_Q48mdI%rtg&p)?UXB=#y zF3S@QrSqxO`h2^s!~G(EY|0B}Ea*fscz^HN+_s}`E2}CIX@3-}U52sI2b@K>NC7>hlMA$Oqk={@i z{hbfmH-u`J+x{m8xV|{?3AwtV=Y{sLO>~vm!geB2Hy4p=W}%OynxTB89%j3P?Gg37 zK9?EDQU>@JvTaD$c)XPLoed(RUUvI7S&LYIH+UA3DtDWd>JdJE8C)CUyQKu|@S~`+ zsN71FS|eHOUY^)1Zt>ZyV@K_3xIRm5L!7Mf*1nDyQ8 zfIoz*5bGpFS%#fQupgPrcK9R<0fujfwL1JxC@jOninQFr#!&E_vje|n`&mYS$2npY zJQV1D{*Y5jr1^H@F{%9nD%Af-+OijrJ=1rezz69D#g>X#Ld2){7!zHB;R- zpxf!Kg=xvwZnsT=_xlR&eUF5ceVM1fbFOdoW-IFDUWNK4^0}KS2q&hxi+Q0}Q*RI} zt0C72T=&q+Y)3E_DEv+q0Q_d7W>(CXf`nXZbp&sj0=tm1mg}#Q$rX-Q!1QKaVHr{( ze^8ZmK3iybhd&%c*l0als02#@(82DI?xA(m;mrd`0@#Ia_3m|tJ`}7n7H*ai$wsw9 zx1=P7es=EU&2-!>$nb^)shO3fc03r!Foydl)&s?7#EN^TlTjvtS}i+s09r-MaE{Z+ zj5V|}LECESmqe)NWgYw7F5BAmMbh=U63nD`=74b+?Rz67U@(I?Ve{}ok$M%!NkY4C zu-H!h#`?!nt$W5@$JXvN*J3HJH_T^I#ZX;q!!YzXrP_!Xv!?^e5(%D8{TCX>2H68BQkx|Thb=*r!V6m~YOKMtZ_LA`NadoT2=doe+PTf0kx{gJRy9Q5f3@Gqg$>e^=Z1JhOXF`<1|1c4)SXFODcrp5L`%X0o3iOX@ z<4Eb@V`F3UhYY>G$L@j&4Mj)Z9BflAre*jgpi9wMN}75`fobzL^ffCvN>lv`Jx!7f zE@RKt2u5#LHGOKb=wq}fudu;6T zZnKwQ?!W&YFH}Cf|FrJ9)0NX+|91C)df(dG`a%rTmqj=*T^UpD$Gg?a zbz*-CL0cDfks)vQ{|{Yn;TB~def>U)g0yslQbS5fmvpyu&(J+|2#83RbPv)XIdmg1 z^hno`GIWb{pLw3&d(L&e?>XmxxUcWM_gd?-_QXL*m-4+>CuEUa>_=Qzi*51utMO<* zJ$ZSa09Z%22xBZqKS(ebAw@XBI`l+@@;rEFp!0q*2?kQp5-uhf%W-w!u zK)h@$E^r<83WAwAQgKGN(I4jFw+A&8lVp!(LJ=ge9D6bG0CW#&=6Wj|V!qx%?!ZNs zl5yJMa|)tN(Lh2S=2(lMA;yw8+P=zRDV!^O*eKMa@}BZaJZ24Jq?T=tf)x=eJ|z z{U^!?W3qm|z}`(r4y`9tT^$|8u(j2{zkluq27^9+maH)IPc%IR!)i>_rxy90jJo4t z{1pg7I+ahJ@1qXp>w{+5fQ9-*o!(3pdhe_UFMkP%AUp%c*1qJpvAqjJ_BX2(?fNUF z-sR-vh=i`S`$tE$bt9_*L;@M*6opr{musn43LD66mi@!Z$XB4}&olYyQ|zAs{~k%? z^rH=)8vOoeuIp5Us|y;t&w!gkrk`kRHW;77t33KHDPZ%3aKAHF7_d`u;3vC1Lrs}d ze$j6srU>zH7;Ayxt{fa!pxKeY?S9XhYZjI5)I?gdt?K z`e7CIZO@v>Yegi{2vlqm_fKI}ofBjH&E~G%Pk>|!cD{$#Hh_!g85|5K41gt;(aDM8 zHhOcu*VnvOo8+q|_3^r=QBErAOg4RZdV?CBsu*MSL79u3O(3MRisrK6@`Qq@5MotRz3#TNIN zqL}xMcI=-4@1D2nk_~Z)_Jtsc7qw=FgoTrXy|>r%oM&y!TS?W9 z^aoe-Yb`Mn-=H|+u=<}QK0JPD$gXtrH}Tc9v9!dBn_qdvB)r(h$FlnC`E1z41Ou4I z;RK_s_19;f&|v?f>tC{@vT^Isa-s}DYhJ!yWI<>WfP^)r)e+?-JftF|26maK zMV2lqqQ1Q>o#EHc=#V>P4XJCCoz@64d0EeRBBcc`91_T zF@FxdpKIx>blrsy1NkCTXO1M6>=ob5-tw6rj+ZeBHp@vF{UIT3E_6kP#LRP_|LVu? zJh7YcJmRUp06e+zVR-x);&iZ`zUG()<}05N*DLDAA-ClmoAW+Y90Pw+U&aV%_)Q0)tmjv+y%t*RMJxy*9i@!UR{y3m zJCq_0oq_!zqeG@c#7^zB;^zHlU|@uX zhz}6^E0>34!Jwt^6hL&SipI@z+A{#=#uu~uTxI96*42a*3=;cc6B?39r+3LvTc7=t zD8ZST;RYuyT!wq%&)`bXbDP^|3x+ta&-;|A53H8*6dE|eN0Q+;T<-u!cF9Sa3^gU8 zGfC)m@r_BQVCD01CEoa4;)f}9Wi6`qGfD)+a4@aGVJcdq*6GG3{086VYYiC){f2vJ z{-pwl;kgqH*v)M>r{Td03>f@4Uv%gyS9lD*aPL_eMB{We#W`2wo)GAjoqxfgCLY^( z4xJJFDIM)5(uTF&<{$mt_AQ7KEB4}oo6HN!%cBDm^Fw6_1i~GVzPM=Tjb7ZZ2PxQ( zn{LUevRFt1{z6i|WPR#7_bU=iIQLDFz&|hcNsv&!G-_06++9-98U9qUrgO66>&Kg2 z#bMmGNO^t)w^g0gmT4<-KzHkaIbIXP+8K`bJ? zakvW`YY}SdAE*o3qpBow(uf3sRNwQkr$hPQrhUC|B$=x+QtvQO9__$Y0*hU20-xV` z8O`3a50SaBZVyMbo1}AFV27VOj3}YO0z$Sa@HIBx8M9eLWU+x2TK?i zw>SERG_VoTHlWdriouRQP zC#isx7cVu@rzQSNVcaI2y*8mFb+wq>Iux%CE1QK?v@p^`f&E>QM_C;F(7(Yemz&qC zZ)O>nCJ;jvrae9sZyHdK@cI6l-^;Pdd35Juz8NYZlBb`3yfNE&CuHIg9}8C=QPyB{ zX+sMir>_lu%`o`OYNkl|aJ1UOe47AVP3qa8IypN5uyN!c1*$}@==H~pPDdiVW39n{ zhvSlRmx-f?Tw=U$uODa{Z|+27sO^a2t48*~y_^a;pG4$o zGJR?j?GOtnSdYX$>=!l1kCN{#n4myGRh;F$*`?>4&c+;aPj-(=_(u}V1~H(SS@?vY zo3#GgOP%QtX&fe_>%G|IyZHSh?qVg(h1`5JQE7VrI5(-oHx!ti|CQ#L6Y- z`nI?wt>bo@cqXs#`y~g{1(_nJGwB`GLazSkSdN1f=TiL-M2?=))FTLX!tzG30r6`w zF~sH4SCnGoz$Gf7kl&1ybVMjU`JM1FQ!Y`hI(F?l@X7qQs|e!RqTl5epf71{AxSs- z<}w_OD7Q&=l<@4UIV1MN5#2PRvv+`K>Iz^@v7u$jbvWiS24qycaB+i2OM|i$c>#UG5o+lSyS;`atW9@!HSh? zha6w&*>#E`2WDU2h!BQmT1 zaOm~6Tv)A}!z-!2J3diQdadNa^{xG(&;JA;S|7@h0mPO~!C>!?-wxdK?#Jc^utbd= zsc8<~yxlb~+gnARELpyc1QSlKKC!IKD)rMT_{?ug{HuzoDULedP^Zi-xwGa8Yr~SA z@5DLI)EnoYetf^G&nR6{`A?okHZ#0zt{#7&&ryc!{P#}a2}6^K%&|RmtP21uAyB>`tfmm7CNy=q3Ao4Py`N06dHdvpdr`vO!rWTBCrWUkuaM+>6b;1T^4%o9t^ zquRmJ=Kb$l@rgB+$S0FT&&8*+b|igXDioddog*)U)$gBD(Z+e7gi}L~ipzG8Gpzpi z05GrTz>0|~POR#mW`Q@r&wP9l*Sxdcl4t0u$nxKsa|4yOr;auCHeS?@X;sKmGV|Y> z*0^%Qsl;^U>ju`?Ox9DPolLKfCr(i26jqOSW2|iW zlZ-zlo!`rAyE`CqwUivB#2cN{het$9V8(otyoAAyoiAL(rue=^&|Yk5B>0~G?t_Re zPh-$LSduT`&|mFRc-!c?*S08uC0DY*8G-$}#P4$$t%ewB6Z~V#LG&3sU^X3Q_4U25 zaRL&F1ae`F6I45=;KWD4F zLBG9(XWURz2^J@tdWM9ymLl?IrGoZ!A%WI{gAO%kNGgmW)~?>_b3(a{JC&^Qho3o${C2~E1sVMET^NoH>H7qAHQRLxL#!ufk`c(x zED*@XQ4S>S>11#~IwjQOmG5Oh4C2&>RbU?v!f~H~m#y!vhEH&CJ-K=22B&&u#n?H( z?hXC3{m%sT6}EibZybl#9#xjPD(_MIg?cdK|MNO@M;;%y-X(UQUY!1%%-3m1KXH4w zduicpUwrS;bZ~P%x-(;*r~hOCKPV8DI&{;L-i6l<*9-Pvj%> zWZHl?xBf9v+3<|L@;98OdfkuV(udKhPDX2cM(wQLofb5w2YQ5LonML;_(%MEZ~1`% zBvHtA{)&F@PnEpjG_KK=+_UC4avjxA+@pUt84auP$+=3vk8V8 zT|*@))Y|pzEaFq@M)EIjimNv1M5VMYD0mYZ68##&D*G-rN%Sm=9KVEhVKSp%lJ6Q> zIIl;hhH<8C3kWT?M!V;_`QX78-+ilGR*wG&c_Utv1W%&m#nT7ZHpG5uW8VHcW(}U9 z{}ShoZVS+#{&#Vca*>d z1uFJQ(!D8G(C^G$Lkk-R70um`-i)Qu0(mwXE(~Ff`U@@HIbX8aog_5Xf{J&~lIoR7 z*BS~$1d2&LijLSaQ>UsfITW(iK>9Y~qV8-9X}Xv7-C ztloCv0qd+SBNOTg#_-wex z2$zA0IX^xt1Xx^N!O3|Ri^?hP5!3e9GyWVm2M5pl%hLVAh?@w6;WT1+rJP*_eWYnr z2wlN7XfcEF_De3q- z+hx;3ir2rD|6GT_4P0r`KOuAX(hGwt(^9t-trgXa%z6 zdOQqXzfZVHCgpZTezMWX>7zb<==ei^L0p_hnUVkwQ>0#A@YXa`zp7+sM77N8X1& zbouQf<(jAF(mq$qYi=cRmzU`3Q5W^L>TY#~aoZ*6sEZ&Pn0fBq-vE2Jca#0D1ZP34 zyGlW%XSACA|IQKpPtRCeyaJEO*8lG)vB&kTAKS6{!MxW%#}YYRU--r3p{lZ#@h57k zLJ*=u0#dZ=1*=MC6d?c2?v>;QxYPPBs?1Ez~keb?w73a zVFN#R)2>e=&U^BN$7c|+*~)$6fWo#?)>A)$Xy}04%)ZW zgKw)NXc8Aku>tCxu_T34AHqO=7=ITcEh`NkMKn5Z>wu~0weI|DXJ~oB7o6owbxKRA zGTV^n+E<(PwzlsAu1Jz0I#pH;YU4HfunyBbU8fbF6l9$THM~+zWspETP{HZwVM3FS zfa~A^`o3O2iLPZqm=zPJ5|&#?Y?DPkrh>}~D9D?cMaGdRJb3+!YA8SfQB~vtrbUH%z&;E?9pL;JgX?&JEGRE;0EjJ{cwCg8( zO;<>K{L66WV{$|PLg!=n#BT%+o_~&Rwz45*cLIZ&zLGd&eV_L?qXj8F1k+_Y#8!XZ z-kYq6?ew2J2gIcDuaqwTl8i+mOG}p}R(bn9HcUDzX$(ghcAUo8+NN4tcgf_b z@1dt3F#U8(g*2B{l`Rj+bE5 zqxs!Q=_sLE+x)&=)_24_xi}}bXQOPk*9(86-Glw8i@Zz6tf%u_p72}w=x??*C{*w~ zJGRl5IbLgmx9_7)+v;LLq0J2IuDz1JF~g@%R`fJn%i`jH{-%K!#fVR<$3xNWBpjmU zHDun;dQMJE6zJC|OwP>6%b1c~bfMdgia6}%&neK*IIF>9V^bNa2pv7JmveGb4Sa&k zR-;ENW0F~`$Cz7$C|L?1?S(uN)tA>%9=9S7b-^8}wo?!HM_1i6!cu9Y?+7$pd>+oE zj`exBm191fI${0sw*8y&mLr3J{uR*S4>x@;8Y+KGj9vJ}keG0+Aj*;>lXxV#M@o!@ zH!5s>9gZDsaSYpoXA3p!Ok}^0dD$~ zz#@6#`fs~1>HPGCXs|-qt03fZPTlemiO^|@xq8ztaswc!iCJUY&J{Dey1G*J0h%RX z=>EqO1c_?99o#N+^_Kr9P?lZqxOw>W_DsqvnGn=_lbky0LErjUA&uCTOlV{dNBFeDVUcIU-=)*S6W^CAgMI%M3THF&QPBJ50Irp=__5{lI+ZQ7W4V%7}&OQaBM6*>x1JXY8EH@gI&x^viC`W zm7zIx$s=72NjBcrx^A`K!#jmZ4oAvACYd-184NeY`d@B0ChK{|=L%mO!d)~M5_QMt zJnj4SRghiEsMjDdYcjrjM>gCK&$>3E#YR35+BgMUT0u8vpa`fwqy2X8?)1Rt*;aO2 zfFcnheWqshjI@;n?E}S$a8PdIG{2lmA5L7Cp4~ZAUS&o3yqRLrNIqjX+q=N=3zS@D ziU}cGp#x8zA6%ZGHTBYwt4y}ux7+g>s7~>^{0r+Jl~Q{C_O9)u58duUK=(x-q;qCs zVz#JRo{mX4qOI+1pg(2)>?rjwg}6!Ik8})L`lf1}4YT|c+BymvsDRD-j-4Zb`G-q% z*^Y%{cxY}Sd2n07S_8OYZg6FeQbUv{kz`{l{fn(F>Kx2Ht>r(P9%To&L&J3qv}t!m zEr2}TM;8dHig_KdFRCh*Ee(hT+H6{tL?i$_k(wppaoQ%Maz3ET zgratl6%At*;hk{-@VW`M{yT3Ly~Z8&+@Hf^dP?VK0g-;)%)1Y|@PN&A7r_31hJ@q) zYo9P0yS@ovP4lB70-`L-(OYX3MCP{-%TvX$N`s0>ziiOPLK1NeY%s>`LF5!Vsu*i7 zb$`1Bt1>Pz*sU^qWFAfL9G((fEi(TQylnF1#iOAfy`@q{d{$HjXx<94&nKgyQR}^x z)$4%fTvW`nDv1^aM8)1Q$|<|jHFvY0Bn%8M;XDO}f<4H?3!~Up3#3&!D=@*LC~ z@QsH~1a)W1{TFJZQ8s%~?J=LVK$P2pA+Y6ccc4`#K$_fC9(jJmWOXPmf7^q_TlZr~ z;^TNohyP`fezNX_ys|uJxv*CT0{zt|o?5s5-l=SfPFx;AuMaw=7&>S~stp&lg3zC` zI%HI6?9cBK-rgxv?G={}y^~Oo_h$DCbKazLd0SYU5gHMVNKGAwbP!G{vk!|JNsUWn zEg(dqJnTRY6%lD*F8JZagy8hXtYG@t_FvgLcL&Ac@=Z-cj6FGLYGN-qr|4i)tb0Ev ze`jT)xWbQx9Ic;SsKTS-?X#Ks8eZo)`uA~gzmMau(VTIeI1eYZ1+`z42xFr%>dht% z?Wr{O0EGTIDV0t_vYC5oLvPHX(1c=8zcpT(XDy&R>TnA0{e>yddv~d|1w1bu>>17~ zsN1Ei&O8n$$^~^6pg$^go|y5I3&uyB`wLypMv{S1q)kJ zXJq1lh8o9E0X$;CI`hM&z_PHE-elMj8`*`U7Oef909_@h@6mzqN-z1FNim0@6D#Pm zEBQk%`fp3ikkUemc<*$W3c-~LLT+Ww&CRxvCK$#RM zZVEcTh~?pJAYO}-*aIo$DOBy-@fco9d*t29 zFtvUFX!%g>6zu+Ud=lH$IPdOO#b{(W$g{6+`X$P_O!b_%?M}U`iISD52*;xtS%88v zX-MT37NTAx(Du!IABM+c+1glf^U;6F5a!Rww9JQNW%eE_@nwo?watue43`;lWKxcF zL~3zBB+_mOHZrLQM|vj=Ik0jo7<+xi*uL1>gr6?Na`ysanN4yW7r$DV^e=cd)@?Wq zg4G+mq6tisPtHn>iT|4%l9#j>4hZqunDKj0~UES&tfY9`fsToU+NFqqBs3?@Un&u$31y z@BaMX+hK-&ME3C8`5-JIADhAH0rQeZYWFAfD-PY@{j&!}|E=*#{|8-d4-dsLILdIM z;Nk-5P$H=K6g5WZ1JB;_UePkJccwK|id^o@x&79pX)X40TFg~(H+mT=KMt^3tdNEK z-jOky}6j)?}-*&?!om4)?{wPKRw1PXt@ z2=rR6tviW;w(@n($kJ4qPBhmljKW9*Y;_tMZ-Mp}(T&x(+ksVJ-U~*DzfQ_n>_bBC zQ8T?BMccW|>`&AY%GKX|&XepE+K~e7XKqy4XOs(!oF}rmO|}A1OLG#c%d~nKqu<5+ z$+g|_ErI;7lL}_m;%L|=)|@Ms<P{?$`n_baI;f2*Z=u^QkCetgp@PL5XOiOTJ*OaZ+nqy1V9G zIFge63nZT6*5AhNAd_9`z3N5(#XQ+v0}c;=)6ZGC=%Ys@?M08rXKeKXb#--#^F4+! zTbB6gSt(Qf?5?(3s|1G&A!S63Vayu~wbINt(fe#u!YZwGmZ(4=bFQp3Qx0E4pC8%kw`(_bJy% zpW5Zrxxl)2yu_am9nJCSnBy`&Ond{Y($S4IoD!%~Pz}sL^WmA~Jwp(%06D&`N%8jRolN3Ne8&NxFg!D zAb@(#_pUC;_V%{8KzZ ztZG%ZcTtV8il|b99vmo!c`%n)8&qY1dpbE8eX$zOAH`UyYBAkbg}kD2^Eo9=J{&Xf zdBQTqf<0B)=N?+DFnK#ieu0huJKMa4PlJ$0aCkR*;VF{?pyM z^+|k1K4(bD7*0JHR9nn|#_8niWDzXT`IjEELceb3=d(*&I&D}7UDxM647}v-_HS?+ zIjci9CidbaC)Orweil++jK2*jYATC`bu@Q;!u$o90gvS-U%aIm&0?8m9NTQH}XH&w@Coom<^Wd?6Ufalq z5zxL@2j{2i36yHgO|KfssDN;*IMo^&8`uiI5EH*M5z%loZkP5@p=$KPP0|0TrDvw( zrAC7r_bdAKBz;!}(HaREo!*?Nh&p)t{3XxL$!`-KhGMdKkE(5YPC)#`jDPr-tmK@k z@q+5D-tmHgru;{gzEK2Z6W5a#i2Y{TIAHH&aO}={N6IL9Ow!?D|iv-!_ zWM_vQNo^)3&`4uFSzn{yR%#^1aH2bzs1X+S{Yr{>!6M{_m>Jt}Iv(MHn5_ zjU^`s-_QdUntY&Q3LlDK%D_W{!q1AP1Pb3rB zwrUvl4yEhpPfFMqTbXDMMXG@M)T zI~}&HF)2O;Y~$U9>6i@iK-q$s;{EHtzU&3{~Gl zaobV)(=-fnh<-^Tkfc2W+YVJgBpdcO2y^lH!#~D)p?KXU*vwF-1pXeV%u;QQwynkB zqHw%0ZF93p%k7#2az60c(mTX`zcx-3NM znzH*T*qdaoPP{p(3X$qG{=;Uphb<{-bRorLcx;AQfYwQK*-^9{=;44ekd>oWGBwWU zoPbTmM3lT#<``Vk=m|yLm2g?(aYSd3{w6 z8=a=3JNY0dba{1<(2c5ke8HwfhU$QTzJGKi#NOj|w0DXRNkd_}=W^W%r09W-lR+QV zqKX%omNV@rfko8`L0rz~v~wS>EKipdW>eQjK*ggK#FwfUaXg8cZeABDUrFNeynX$L ze7%6n0d0{{#i#)5oI-tiRMLfBm8-^k82RC>LTomqbMLN}(gA-j|Fkyqr%5GMK0*iI zlwTZ7bNjutG`!jcWoQ*nV=&0jSpQ|^TlN=jV+GUEaB_efn|k}kO8CH$p~4dCX)pXK z34XKAbsh%QEj}ns5UFIYH?;>`Hoxf?yZMy#WcN+_M~C`GM7%Zf=cKGMfh*ifS|JwT zbZuZ0p9k-l;NA`o6 z1wVS!73R)uld`e1vvP5j7W~NBzZG$y+_$&0FR9vi0T_qmZ@}%d5}LK!BGa}~hz6Fw?Kou1*Lbvs{zTWlAJE@jSI4`!xG41Lx|V)3 zS0d0T<*p{iFS`FK5C~CCI?L|wko+In`JV3oTq$#jp2k`{#>T2&pkM0O)_Z7j?3f&W zGPrcW$p+%rx)}00t}Tpa&0j%-4B5c!(@F+jpRZHzqKu*GUuOdluRGJ@4w98j+Cy7( zjiU@n#}~URK>=_)WO_gJF|LuZO6}(~B3J6+*2lOMm9l445o~(rC~E(VAxx}Q!=}OO zilqD0t!Gj#+J9A9-WZ{0KMC0Tx1YqEOrOam({u3buc!6>&mcIZKxBVNm)O=u&-=;h zqu?9trTHp=pAQxW-``=;k7J2Qkr6D>WYeNj{lqMzUm-I_VVxLkh;$<<2OAQ5KWnS) z+1Cq_vK<)-AlNt7^D~;5{3fPbN_29HeV{{8OlB8z8v2yKI+b|i>TX%NCCD-=EiImY zn}k#^DOeHJJe|_8jD;01kmS8fK5YMz8ZJIC_Hc8kJX~5?mwTOI+JZnw5u9HO8%0rN z0|xtu-wx|hQQ^1}>I_gG$~Rq9adD}VOU-nIM|L(RkCd0T4XEWbEVh7;@mN^?{P=lO zlt2l}1TpJ3w2{0dE71rbl)+VT!abTiv=4`-iDQ?Dk579%NqZ{`i#Acyb6p7;`=lj- z%VJ~i*`zr4ZsLk|_}PbKY0GbL3%ICur{@XdQ2jy+x4;5WTq86Th-+iJ{CeYt* zsyPDvIL!>_FLiuws-Rqi@erqrl`9zIE?OPh{O7%>hej=beJUr#ufri{J>IQj_9V=A zY{a9zRTv4-qtC>DM-UAa(VPJe{ayZHoaOvZ%B&1LtzQ>%TPv3!J&RTLm57$)$jHoC z3Za}+H1rKS1O@)sY!7aL4hCEmo=Bl(O^9tD#r)Deb4Ggj+x}KqdvhLg;Am@wRdYB% zb|Bu<+x=&M4=tCz0+>q#WNAe|@R?#8eLK3$){@aQoqtkmUjAs(tU%H~f3_6grp^C+ z{}eDoyC0SrKRgbEjD-eH?oaA)1OO*=a2fb(O&W~$V>)r19|tp z$NCuROC~%MV?@bhD@N2H#xVp2nklZ_%=Ae`_^nJ}zwq5udxSv3%*{W7jwCZ>3MwxeFYjBG#V#o4&up)Nf;gmh>BW`6AZ2W**8b%s^D>N^6QlwnJ>lq zfiv^%IH?Ag{jc4q2;y^Mo)hyY+tBRn2J}lU=KfVACC;8CY7k|{r@gDsAmjZ69|x}9 zbMFaI^;Ev15OgK1@0ICafb?$Emz-`MmWzoyl8*n%8l0Zqu4nx84%?OkxZV)P5pDFd z_m6ON`_Y#_ueKGU>k62;1vxSdd!*pFaTYd;FQ!9#Us3XBoedfb`*cL9kS(_O9t-iO zDwO}=D6K9@^Vk{l!ombB3a!rV?Hifv%c*&_N;|8)#J!k(FEBGPWuhQ=L%_y9k^(9& zo*2esmCh+BKYfv|0nxmi&lOP_EFPViZS*K=f@~;Y2?ZJ%;dybnqtf=>pBug>OXtX9 z`MR4sJ6F+IlHuZxDAbl(|q1Yc*mo&<)z55H3YLhdojHs@c6vu-QJoR~-Z zX*b-J_IGrN>tb^Mo7`VY{69so7s*3W-NZdsB}(?K8=Jdhe=I@dtjxI;tFhJrQ&K>^ zLuT(SGr5@<+4(gWREA*z2xf~wxh$kq2%7R2kQsG z?#Z6i_nLHI{^s!(yjH5~EAF{>zVXVbOYJM9?2@DsMWZg*r+56xKp8&CAgkaAmIJ865<7B^fIv)=t+VG&c(Gh;>Epx$2n#7un+c{4uyR?Z?DL8xSD zNNf)CX*-dfV@tuxJOLo)F~gzVqGTsJF^%DNf9l65SpWmsOn}{MF}CNT>>9oFbhggY zSWB`?%~o^utW}9cGw6i)Gs&Lc<7G34kRO=Z`FwlW@#*v9PER0WL6QB^F| zHfozBy9*qbTj>1d5jbRJ3Q~{&i`GRh<*G^7HNclfuTN214*tOS@Jo=XDaWs>+V{|b zRT!qRae$m>QcG*gQ^)cCVMt7}=vcKn(8+6{KZWP4jZk!m-2d6*s&Zv#P}c*v$!l;` z+h{jRz%i?!!eyvW+&{n2Ikr0fEwlW9okN+WO_4^8?f!ntgFdK*%&VqORP2;=tq z%7&I_@xc+pKKa$;fPos>f1rRT&ouwfk87{_(9k&4;@s-$2L}5{G<;aMaS3;(dK7=j zL$_y+m&gL0ac|F$qe8OUfU}4S1&!N#rQ|OBy~s1i?{hk6G+NaS%&EP3iCt;#v5++8 zfB7Wx-IxQbsN8)1c;==SgN5HV&QYbgFT2LlUbGm$-nERcNpIc7hORBCNAc{gZ>_R! z`$gLJj~_QZ`4A^QmfFS>pULCUjxF>QlJIZ=H?0Z=&FYqvh&L>U_67AvvhROWU!ny*&>?OK*klnG&B zJX}t^9({nvxC}s82P;u%=6hff{dO*@c&M?}1T%IGY@&Lp;l<+8G{tMz7mmxw*iY2y zAdJZ~iG;-K6Taz}uhFYZ8VxiSV0_)plQw(M@2$<@IA2At#o=?Zs^sX%mzuiOFgrJ? zsVisiD6ZgWTvp?{DQ!$u#R({@5WN-bmG@C3Tl;b8zAEDX5xnj!?3a1j7dK-rB%|ZZ zXIpXQzBi*AuP5kHw#C@UPeW`j-d9>Im(twiQO6n=KY+d2(4d0=$MNA_yw^J^>8g&) zn%1{>s4i)3N<4E;FXN~vZE8)-+NNBTd&>FYdeEefLX*r;QSE5oDG?2$yS*sR`QnNi9y?m0v%jkcn^3u=tu~iVS+e53O zSS$TJ_^3da^_GEHn2yO&rj5x}&`c+zba`Y}AgpTntbXZeTy~I%jz;BtiUd|;CIdXD z6kuZhy|Ymf8PQ!i?pn-#ndTJn=`QGEy^fYOoK#-l(_n73*q;lBQQ0Sz>$!rsV zB|7cFvp-E#g%R+b`H`7Y;{Knxto@AgauCR(_d`t(wUEJ3&p8l}M4$a|TnPRM=XH-U z63Q@Dm|XX8S_(|5YR6B`F&YawcbJ+!;GVo1RP3WdtNI6r|6%v+JBfh&s+h#dIIL=E zq^W9{(RpEHjAqYjD+OviV>l;XQ!Arn_O`z%_MWsZp)uLLEac(kuW0Ve>-qz^+>uN| z=+{=AJR2LBj%tE$xZkun1Mj9Vmb-=dLD5%(jg^I^c>@&>;P^_bfU5hm-gDhb} z(ynh_QFjQ>?_XenTd+e`2IkiNQdv@dSoGgHXHj^#vo*|x<&DVOm<2UMCxmWq{HA-; zaV4wfEGN)VrO^C!pYHV1vN=0lT;27T;$$Sjf;G+BV{I;;% zIV3Yolr*iYr3H`ZYT(8FJ%HQJjpgy#2Fx{Los65({8VfgQ7>o&{8V;z90rB#rmq_9 zUd&3DmWnLmU+TUPf54dK`6NrWv5F3Kq5xJ}es9^%+9zk@A^L?AODv^<<-B_A68-(; zMEG^5gaG+Dv{%!Vd3NHXY^y})Z2{tpz+dvun?Tw$Fg0$fZ;(;et)1O|K`B=~Ma;EO-bS+yj@Rd-)y$)C`=wZTA4~XDn zXGx*RM?I7{AZ6cIe5GI6zpUPuqYOxaR6vQwPI>vX0Uo0@x+tP#JcR5a5_XwN*Urps*(P`WAOnB+U zB-+~A*Y{(#_bjV<-4A$O_xqwh&BK`bvS z66sb@9Y+LMvKP~mGj!(LQE&dEuEir~yH*OV;`{wn1MaF0nfd{IC(x|5?4HwmS)bz| zrsC(!@2WdL?RiZ9vR^@Xbz-btKg+LKETJymzdBODs-a86GElqRz?w9WZFZ?iYj9ExhRQl&w+h@ zYX=^+ZC>126^*@vs;`C0w5}OtJJ?s(tQYU($@n)tlJaOw<$ec%eynnB=h~GQ%82m= zWoKMX6#oCZsmk1+PN%j{PGagkY`=Mv*=jt$4<{n4Hw9r{omFcD%brMzv~Z+)R@Pb3U9|0}iE z=5O+8{)4jr%XWNPW)!C`Ea!zhsff25G%%qK-#F&YdVG}f6-j`N@qWexm3mkNzpa>$ zf;I@oc}0mTE_CFjG!$BG&VAEgR<;R36V-_xe&_Utzd0u*M|ld1a)?7jeX8lXH#42} zWWm-84YQ%xAzMsrBWb&dY1PcXl-|)3(Rpy{ic^C<2tT68* z1|YF06XboZXiZw@P28b+h2{Fjq>xZN!BvkP{MQ4t@gSjo+CUXo{EzohLTM5mY z!!9|qM%KHrIW1YWPbR@+WkvXih8^i_cA=!J&*3{0YJK1*M6vO>hX-xO+F+SRlAI?(TN_-BqV*f4jc*AJ&}XzULU@ zdSXiV^w6eU(DgMpKdQBWZ>W!ke&NgzlU)lIF|wN)O!3B&ztJH?aGES+%3PBPr%Z39 zbGaV-A!1+@)P{?#kzc@*zMQ)>WNO; zL(kosit@|w0#0vX0S%C$RUBhZfFHPfLeTpZZvMc(TnTV(NSll6iO6IeOTTM=jtKE< zj;G{T^u`?dK)gxIfYOglhNBFQ{8So`%3ynKK{KRG=L#oLMTFzvP(rWEovqYj%+^xn z2~`i2!!J^mow+S}V#<_pl)hSgP?M29FBY^?ux5&p?Dt}$OI=J#$;9DL64D&Vq>WGO zH(A)OQ+yxGTShAA+n&_C%L4JQsi*@EJ|fcpdR=O=dk8wyyH;dN0rdQu9A<7sM;~;$ z{)~t;UiKEc=!KC0_PsXfl!ID$4NJa0%T~dzTljs%ZvGME3a`oA?YKnSj#*ca?_7tC zeb=(!Qd=jk&A_t}_J2JC#~Hg8oRG_r>hD`isQim!i2wZEwf*F?`?y1Hh5hf+ukBZa zQ&V1HMSKx$8u}yCTV)j-<6Gb?B}Mcer3^K<_PVV4OIwzSP8F9`Z_*sww%PArSEH<0 zWDNC-wZ2Pc#4@h*gI08DndU{n@xpocigbb-+_!wyQF?MEzjOCL*e*u9++)a z@$X@NvQgFgNNJ{_y>3t5Jzq|gUR%(DR$i8)IZUU4!-^zFpqAEWyb?TA+uM^b;Gr7t zg@ot<-ycR-^;EU^;iPGMy5_H_%FBPc_~(8cO?Y!ZM*7(Hv~{w?{I0z{2BrBeaE)hD ztCP;N9nrJ>*8Azh#_mpBQ3fmJOV`DD{m{f(a=;55ASdyTj1229W_n__c42E5<$^Kv z)t{bRUP$@yRpYiK6$Ees-g6{`kbFEA%^a_R!==(cH@JABENhHHJm|-^QWjI(W362r z`0al%KHBox&2_38Jd=9Rozd|LL`V&djtI||gL6^}e@txt@Q8HV#cxSecMkT?s)lv2 z)GOICmD|$^G3LV~I84=!)IFeZe_zOhXKB5s8X;>2{l#Nt9sc%w3TvX|YM)e-1%A5A zr+KKuk3q#RxZpJKj=hw9_Yp z^v}-EQ!&a3Kvk;J=x{X_cxD>FBMTU0{(vfUQRh0c{;97s$SD5t%)IG5?zf7Aa-F@i zA1gDPKV@g3;bjVQhJ#2dvo3VmGW z{=RoOW8K!`h4E`e?QrA#-!ar8qh{jU#sS?`;(_k)Oq(nd2kWr5nhG;9fTdYbLJpB5 zP}R%#VQY`iAS%%Mw`EXGbC8+;d|3i8Ikx1EHn4E72&<^NG6a}}fBEy<%>37(6=GTn zF$k_&vzApW-&`~9(VX?&+`wud1;9?s&j5;Y-8?ijK&U3*+ZpJ}n@-bS7Lo6|KH^)G zvaSO?Qf#HgyBhZOTN$p4-4}@cO}&M0*EwZs8j6m=V6TgeBNYOE^a>7-r?$A3F8vUO zOF%Ml{XfivxD3t}p$ghwR2EN>1DBdgPVbhcq%JN&za~!bxd{*j?F9c?vfo=&mz<0{ zzM{Z9ON{<|Dh?z!OA{H3q*nQLS?xP(uu(*2WWJcYL6k3Jig>P&Tew!GHnZ7Uq!24| zpd)RJPT7UM0i~KWfXC@T+^V}-iTdXV|7&MWq=FgS14dq7o-fG5AvyEBW#+r4l-(lA zp9!ixKlkut<)UVuFd}yq=NN@8>lE~<^{(M*8CgqV%Z!?DT5d_KO+>9f8?$!JRX!W- z|L(j=EI$)zbhl8SIj0;_n{%!I6LpBEV{Ki#t*As$M#_;i{Y~X&nx6xBupupnL1dS` zFSs~ZV5>ejqWPUq;G2&AS0!@-j5xmU|NhOaaRe+^MIV&G)?*s`Q)-$hD9qRtmDKCl zKZ@B^_JSAkhe{r?UbL*7s?B`T9^yj)#176}p!y=~lX23H5rI0NBj@;bRI z6loubyMZBkFFx<5Yfmg*jyj?Y+jCk4JaON4J^J`@Gn~w~E>G4KTtNO;s=5Bf zO!++ucOAGU%4&7AiLORpaiv`#D!~|1I*!6-{J;=Dp?ZBJ@D4Dfs?-=rut>v7Psj`@=!b)w;^p+sC zj`5E83C(VV$-z=h6{DlUPDuCrLnVGX1;9y``N5JMp8lzS`$i%(L@GZaFOS4zyG_Bkh$x1cTQRNeHv(;-UOT50+v>(OZOPcdpbbZ5Vwjj6C z*CrvG8H-vpR6dTU;Xe_o(j7m+byr$291Ty+Pj#;E+O%6_skhSy`ol{W^ z{<>%&A-hGN*{wC1Nd5=adqzY9`lM7$b`FAtYI!`Cco>xRNA`y^NO*6AWYxU0`}$%? zgy^Gj`jTRaMe?X$%BCm9k_*HeNJv@}`_|mfi6&8)3&oa-uw>0_D$PS)X@#vNio;53 z+LE6o2gg(111sQZ!DX*KDCVv>TW5zX>}%_QyFyQ3QITcc30W3$h_a1P$S zV@!UfV15Heca7=?pLV?cnHRA;U)b(x5%Tq=_cqPx&iMv5Lu_tus3{%_83lYjOD!#b z)VYZhijku@e9j~(8-~rt{Xgrkatyk8yNR|mof~aos&bPOO}{q{TO^|-!RH525|A$ zOp$ZWrT*lz6H)cn!*BV=>jNn)1dP&Xeu*lf>?VR61H3(_rIzTr7Yr_(vo|ry{jsUA zK8u-2B>#y4y1_5nTAG!ATyC;G^h_`KC93z_PI}?1h3+ zUs$H=R+uB#dc#i+p=>!vx6>NPGns~Bb4qkIk!SlIEc(Fa>XP)<>;5Y8wN?q7a;9Fx z0qgn}m9;1B*5D=kS~lCeE%oiMT5XoJj{W--=8zGrAU@tBtl&(m>A<0AqJK(mQcHp^@>^Z|-i!*S282 zynns1Z^m7uWQL6psb@j7YsNg31eW7i`RfkTw7|7-0F$@>V7>=SNAU?60;j5ufjV=6 zWEy_x=*Nx1sp(?zn2zXF{HoWh&YfaNAb*{7vl7oUyZiehUq4SQNSyoC?RS2Ak=_Xe zy&gpkS5#(i2t4%^Wy!p(iIvnS0>6lU)ME*_ZA?uYTh8~rk7m^$5z$aPokm1u`7zAu zq#@lk+mCv?LqXrwYLu!6eH@QiNST&DO={TA$TRh{5~>ryY=HApieEIiL`F~jn2Qx! zmV|lG4i~dEAg9-e9wqDAhstyqS3b@EJRUU8GJ z?BoTVL-QVP?8mB1ogDFm8a`SLucR1D90}9u`Ov2{LdqET5aa*BUZ`3=N=u_5uJABKy+fz@RN#@ zO>YRf=M!QZX5Y*Ti4L#+aV+$IIg)>Kq-4HC3@XM@P$Io@{3CB)ff_dVi_80nIIE5A z5p=Aa!AOu0yj=o)hKSwrHbp6`dEe5C%{%FVvzo?rQ$y0Kmd5Xtg=Y6Pto$Qq^p0C> zg06J$0tq^~h?0URkJYR);$4pP@AYpkZ;CA*fcGzQEGS=NKUZ_9xAZE`kh<~lD$go& z&o}lOOk(3XAV8Y5+xxRgGfkNc9WY|Kxw$pj)OIYUCw;L`Il5bgqDP8D5C+>H_pkrG z=s{;RGUj~3t!+q{%k4-C3mihbftZi&KJRI-8&#(M@w||6t69~#H#I`WmyF;v0~BNK zuNbM5Vw39wakuj>M0-hDp=p7@RzYkY8yY;h1i;_O5$X6G+1Y!pez^!7VVY!6(hS5E zm72CcikPgB4&GykLeC?ZdeD~y#f&%mDvux2PlKs>m*w5MewhK*OOxoI}_NxtPmv~Lkoc%E=u_`@%UGS3(?BUEpr5CT( zwY4gwz8?`$@5W>|XC$>Tx1_Bah*z!kp1J(zxAiG$L;r_KSTsEKiTVEza-;qqcE9J^ zPsS7Q0lQeni0E&!3PTq%@_s~K9tMYFJUaOtl^j6iqKhg7A)?{%h8VX{hY4J*Cwq+A zcUb~vH&%uH(Xuz{NLQIATWIB|n4#emPY(?hv?S>fm&Li(t}&Qs&%CK3ptE1;{j=Ys zsI7-2!X4%L3h(l>sOse4u2uS-Dkvz(<#DY0yz+AHdSkJDj-#uuAN}G1^Q;*~`?Ioc zm<6xFxdSkZkGdZyGDCE9h&XfeI>BhoRCnS;fg9anaNzDx-qBs+*Ghvti`%uJR`{e0 zJ9w%Tj21tV_^up$lIQGtH#jbmXj;UO(&)|kAd^)kT z($Jen+L{z^m+}@>$VL6K*=_zEk2;#@`(P|XdF6sZp>uO6qZjw)aDb>(RhD?Vhe%#lP@2ArC<1u+4sJjDm0(j znH|+2s;{ZTH>ON9J2n00#qvt>)3wYHjN{=NoD>ZpJRp&7{zJjTb;Kp_n3#xOW_8Lryjq;1$C@0FquMeFfi6IeX zPJP`P;$mWo?E9)78}(y&mcEwzY0*+S@KDQ2{EEdC&6vTg&(%sI3H)4!nIKq{D6kO`UUZgYXS)uh5Q zA*PP3hT(Lco%hP3GVPDEvn%ND5?o+F2!vB5e_eApPuK|0*jhU@g8HW z)TI!&!%U8YBdP_0fC$7JB8dTOFR!~sPo5i_2W50*NhG0SD|yJ-g5e70gWTTRbfwCf zU-yf-f`=mTM6FOw&8={SU4{DwXwr0jGzVp|`8h%(T}-9pVk{m*nc-0j$nyve8#<=B z%eQh}sxpxCr8J>R_Am@3MfY<64cd_McHJ}{{;n#z>7hlIG<|RzHE$-vXy;UbLDuY> z)L3V^z=HDz(?>toJ-BB!fKCxm2FX8w7zBPot zwz)2-{*m+tDXC3OWnpPo{MC&RwDCykP2i7>`0{Aop2HLNXUoYlw?Oe^q-uOghRcr--YFLH!D*JCj|ijF*t##o3}CLB!djg*VZ8M=v$^OZCz zwSdzbqBG~GG;Rg@W8g2q0&l!#Mw3SV?Ro$Axf9n=5@_JjHm{iRT~1DpKBqW8A4`?v zHd8+v?v4A+Ym}=0Zp_F)K?6!AQI`sCa!Ljrs=#!jZ~n0^Hd^uJn3*kNlPQ@=qDLvz z(b3ZYPx&EIN-0{DH`A- zT+Wk|leCw=C39=jn8tye^!im98Au3^H#%%rk54a8j8|_gJls)!6>ymp5kUm^R-`Ui z^N`5C1xO{@(Dit|DYde`PWhu52RwhooV!&NvHTKvAo*e^D73`$JMech@|QY;Ycz1* zg!)MIA%oGjp_qRFfv0+HA+05ObyD4-;$n_^@8&2W{hXof*CrTZPVQpwQn49s^S^q& zw!F+ZI9!#!VFU<^YZc`$p2O?u2{!yVek@G4>Oi)TGvE8#DGMRx5GsqxJb^!No=!B{ zHploQUFoOYd)q)LiV2%=TNsUTE^i66>xG(rg~UESGbY)S2XanZkP5GwhC^M3vW3P1l`0HU2I^zgVRqZL4iH6>cN zp-%c(LiTUG`SFT=-)+~9J$BDxb8U3BFRQ|cJz%m=`?i#7?~4N2$j7E*)<5biku6pP zbwWjvVrC*;oq5-^0LUGMg-*}FD1{t;GNvMHHw%A>HXhu89#i)6k?N`7UI?RadqP5~;vmi7tV`H$r zuv7LuROu(`k_5vtqP%R``_Sfac_hL?-mEA&H=;9yqT^LVK(ozm0g<$YYZgd_wk*%a;Q2>% zOmg{+v&3I}RMZerEPBj*-k_jUWgu7bi1`qY4Op6HNX-;hjLo2mZ2GsANpfiXlYOem z!uS3N87_zI?{yT4+vUimv00;yb()z%{Lw;Nv{?eoxkKQaJR%%0yrG#AK8U)se)^m{ z6e8*EXNDXzh*W2CZLzD2Y&jb0OfwY5Bj82KJA~wR(TabS{Z^1E5HRNo5%ZJ#K^aC+ z^1X#GQR@d}aMm1rQn{73Z^2JqWi?rVC-@k@H&^XT2d*l6@oJ#i{nyMlqiZ;+P{(Fh z1G8{vC>X@rcpAmAUHZf9HxW-6!auF6qpUT8!V*mbIwl$2E&7N*pATCtj8lZ=0wDgr ze?(KZB_hs2HpY+Q@K~-7)=%H^nLsIurtxKOjTWTM+HSS0FxpfK=8f4+U39AEt+0U% zCWY)@1zu-orl#?g_j&61eb)qIKuV=yr{}~uypvg-)G3Ym;z;kN8~4vm6>L}EpM4*w z>Y=`%<^OAv0xqpSingV4S|vYKUl)JbKHd*a3!|r%Mb~7=<1t#B`bw*Jv1E&BuSRS0 zg31rBvd~=l!C#$VwY3B{9UCdZ{_xrBlBk#|H)eLq;1P8gMX6^H=YP?#r-73^<#q7} zqIc|cdpLj#U^?w8y_l{Bw1EF!qa*h%0B@c*FFjNAyY6~>Bks(XBh8QZQO$6_`^`jb zat-YHa%XmK36T+L$Z_n+NwT@1(*IIM--wElagmafoWh`umK`eo^j~+d?>ywO>x@L) z`BRN!e5Fp)OzJ?2 zhe6f@d$~ML#%Vf!OHwzSfN`wsL?cwI7p2!i zTNb<>Y-{FW#mv#VC^NoI$e)t7-doBpWU)7wlKn$fQ86p|nuf8#$fapD;CE^@Qgo`I zKN+~~u9&FK8-UmyVD1cZrJnNrWTg7Kkkeu6bTE-n*l`*e(9XDq0U!MFFU239k?2vv z8zp_j4nEm=?trXx7^asmbz2$|rCqv15t^!&JVO61L%cQM0P+5=rz8A&S2fp9U0Mpg zI2{F%>>~u^!y>A#rj_vQR`pf!(RsL78@XNkr^6qRHC&hD0$a?~#zY-oz1%D0%H|B* z9D|W|ijpe%QNY<8DbR~8JSb=e1tlPSg-Pz6KH;{`^g9G-81rl2Wnm*u}{z)4>$hte0b!LSP&K7HrJ` zjb^YoRivTvjU$P9tJ1y2Af}u+N0}kU`JD1~s}Nrnanf{nq2dE3hWT*$!H3vbli^I8 zYbxU4BEvwayJ6j5w?6H43|2!qdhW2S?lzkJtb@ZS2MXwoJHefP8|UwQRv>Kc+WBT+ zsUHW;+>Jh`zPq$087vk36PIFKRp5s|g&REw(8Jh#mWuE9T~T)V-2wiU1q@w`LJG2@ zJvaqNdB$XMVlq%JkcgN&ZT`xLi6Fk}{t&$v+%nYj_IieU)!CUxBHo`cf)~N%y}~qz zMWHlY&NUd9550H!s!U0ydf!?RnvgAd4`M1skFyvYwoxV{n7E!+hmwmJa%tgQS;Zxo zoNhZ)qQ#r2e&@O>gcta-+(Na&j*^@TI8ig!YK#*T_o*)(xbx%wtILYDMO5k3NGmYoVj#? z`b->;Qo1^>1|uHJ8kyj4IY^o92e=L$M5d4O@01!eg$#Zsk2ySL+D=FGf|YXZ%gur` zu^xMpzqsF6j^=1qh@GSQVEKSJTCztCuRznD7XJS}PVi+o?@n1}b7Z&`-_Yq=o}c>>&?7 zIvk5MJU^l5@~;)(2zqHb4X$35|C`M&{U(Fzdb9xINLS&$fLoG>OPem}s-vk*WzeI> z;A%rSdx7r=4slefy613oz(uKqxI%o)GGtlPef3lL>#hFT?sW1zgq3-gu~sQdUW`4y zYFjLCYeak2J6zI#2g*eoyY@gC4h~KW=z5UP(Rt>b&^h!I2SIL zM(mgymPT)0UqrSrSQJyYE2-Lix0=mdcCGC~Vk$#uEPQ-@URcB_Pg`T`a5uK9tCXmn zzWnN;+5PzF!JzoS2k%+R*FXbR8s z&0Ykx1;^Mnc7%(2bo!s~4H zaC2bEi#@#gnFRVGdOb0@&x$;##U(4^(eeM1J2@l1zM9u@JDZ12etHyngjE4z^5d|? zJ-YqgF#H}N87n(-j%%;6oZZ1461_^S9w1vOepY@9(8U*=N`bP(R@S_GF(I>#)K-5v zy>{w+0o<#oHILLxiXr*MdFZL3yG5xd(-FxcW2%S4a$qQXMM*KaBXxCgmf@2Us2Rt6 z5`Zs8IjdoYR+^@rl$s0egB5M3wlJUeM~x8Jt5%q+`LJ^5M0>wL{9`FD=;Gs3vhZ(t zwxo=4U#{L4G4w$96>52WOg;>Rs{s6lXV59SGN+3&xB~id!&NiK5~teGfsMaR`(lWB z9=K)0*l2$4qDfEqCk^XyayhKU#OA*M`l<9Masjwm4`9-MD>0?}Dtc+CSMrEy0_d%MYPTIk;WVDo-C;%C8%>m)}jpBabsuYI4Q}O3{WT^mlKWDoB0rvSSj3~fh+Ad^ZYyGY4#dwX$h4Jljo?<*)% zQb^t}I73i5ZM}#!BO-Y1X7R1!Q7z{dkauHqM(u5~1XPdnvHLrJV-to(G?--Tq7tfN zn45lQilG7Xd_P7bRK~RGzVE_+wNk}2U%FRd%O)Sq<=$%hyY?sY-P;t8(HkzlCY|CWBK>o zBmA8cl}0T~o<$JSYc0Opvoglc4cI#ue4Eqjqwm^Q62lUv zL!gT*iZAg1XYOmjR$WnHXM(~HZlW>DK(j9z7@i51^(Sf6qV{6B7&|&bKY-&(w7vyz zzj!MXa(^>$2KB+(1pQvkqN5cBb?#7ndBN+|c?a7R6$J$)nozr%+Jd@*_;A^2#v!%W zxbs3u$l3T?V&>hq7Cd)21)=<&@BhFc+#7#I<+5~wMC|IRurY*ogHc!oQ49f zmdCgMhHC{z!%cVkv>8VXGuBsGF*YJtc1mt^#8CB^Lnoe6!&%){DsE^{KAiIJ3Ph`? zfS*@84NA|+N0%S92BBB(w|$ceY!v<|&R0YK3T8AWZ}LF~PinMyKEur;M@*}QmQNPp z%M*e=r+z+1yfX4vcZabUf@bH=5Sa7S@2`r5Nl#%drx&>M18Ub9v3EVM zAucXQ36*>As`8|tz}!Hy+#ky#Og9HaT;G^yAd3hhWOAM0CiHVsIBY;n>iZP>u8Kam z5p*E^L5|zu(LQ(p;(BN=IVb~jIG7ZyMOnz!<$-!)cc<3~+ARNFAH)jurRwgwGAz@B zTMZWl}FyKU}L~BxCfi^8XYeLXqmep;RW78r)tmSE&^I?fELlS8-Jn9J zGpGcl{6|a3&0>vWE=k1W3bSXBV>25LJwPWW`P%zi;T|b=VA-6BBmTu1bO)L4!xF(W zK2{b3@i+EK>tmU#WbMphlli0B%LEQTO^vK!5FrItLGwWTExjXi%w;`M_XdEZ+?*WJ66qw<-qzWeTCKFJBWUh5N=i7=BnHfTH*z-vsEY0Gb7!?6bs9^V)b+fF3`$qhc5zJ z2V0hZk58pmA<1BREWLicEoF~dp5~_U=B&`+W1FP8Om%J+(H|7r?*x*qEWgsTv6sMC zHtbH4ax&QdeCpTQNK?jS{a?&^A4#`9)z&gc_URHUEz#=E5v2WCBI$$iZ_bnU%d>@U zT7Ub~Lmk|m2*SfG>Zrq^eU-ibp0On&cQ+RFQepxuD^wCaODHOK5mJ1<>opXjsm-IO z;PR5(cZe$}ZN{;5A9u!|Rm^NT9r@?#L59^U7+{9(+w;N_kGkBU7IRelMv~r6(qyTZUxnK->!>ftoS%+7mY@=TRxtnRM62#%5I>rpy;i^!jbfzleBtHSq1l>+zuMVzwD@ z{#?UpcJk-M%XTl{{BMkNz((P&LD z9UDzscm-=NJc4Hy9`73#+7GW5ZozH~-L8zy67?kdR0biO)rMgzSOKV$4nIO96Qs~D zXLb^#gDHX8BHdMI+Ng?us0u!WT?6u%^G725%>Pq_mM{&oN>?;|2WF0lUB^z?1!l3Q z=?Y9RZU0C4!CN$IUN1GFF_+Ej${$7|V#<@bgLQsPPJ8UQ9{RLRKWbgycf=~`17Ec; z7`2Lh93JPT>G>_+j)&0ufrJg#MmW5vwStu7FmdU6CUdHl$%^=&YAq6C%<$wX&b)Z$ zv213Z5SK9F$WGeF2YMREcs~aIG8D%QkR3E^H5I90;6n%>7G?&r8@BCIotK4>0cLG^ zrIx5M+33mx*G{zGF{T%Vcx(M?dBbd>g*uKwx8Jtac3-+_IHy)8QbXvfkWhIuA@xp; z(6DM2VphlVR%dE-FT}fScCy5@|zWD6=SuD>a z=Du=EFWF5mtwuQ?ahW;X6*PM=FX>asI$DWc@*XA$)FP)>u{1WVac0cVeO?JE-9RX> z=)(G!ru0p#<-OMH(>Lu0m)Y+D?}HwF)qilu9!{+e-+2}aE?^j|V8_E;7tk(ul(|E= z$@nXAAdU!rg%XPm7{i%4p+YGP)ZR;<*|M{Og<9y%Uyqf)YlUrKH5E0A2Ol~Muw?se zvfHHeP8q5SE+BWbkg9s7d3g}Pgwhnh*nzeOK;_up6-E{llTrD$B9@360I1yDvCMF8 z7WLP9=E;xd@mLijLh?#_k)2f*#br>L!G1cZF&CQKuIdn!M3c++5gnStjpSA~4mlP9 zm_9o2a-G!BohPDG{`wjzpb4g)(&Tcw-B!>|{j3H|JOb(N{71HuKWTc?XB9uW)|Fi^ zB6{geT}i9b-}xxa*snrh{pXKdRgKI9I7TaM+JN8-85X46{)?R+#S$y&6eCbi&648L zj+A==Te9bylR2J`lnSvUikXckv8QJ!s8cMGzFLLYhVYeJ0zia-`X{z`FPFz_v zb9Px$+i5MmU;)VQr(*@~b1Gjzrq1H$U|2g&Dw25AWBSlWWjB(gO8%FCfA9W;C{4j? zrJ1m$&5O~}ZpQByCtvYcsl4%r;wk%H2joD2GdnNyV^Pc#vB+AAr3km8^C1WQ3GR^yKnEn`_6LgG^GxL3W5u4nvUa*yaAF2*@%g>1=;a1H z^lXjSWn9E*I&CZ)uSaY>84c*m-EOAQ%5nKzzl%TfComRqqg;RO(Db^wrtWO3r1BiU zG9P-C@^ZLyc{Z6e-m+VN=8dI%!@;Bwjn=_D9hf&-On8w~+Z^8K7Rosv-V6~8V8gs< zoz?CmV6Uz$AVb_;^@&;IRZ~(rT8-&dd7+mS#JGYtKRM!G3=tziL%)b__nS4)a8AaL z>vzXukiFuQ@xwvRZxyq*6mK7o1pH7cfqs}|0*hRO_K}YL5M-d}JV( z8`~=HXLY~RJ~h+5IlhJZM;vb^M63a?fER7ihl+?ghaK4}U#}+71CJNl%8Qlsvbx)g ze+wWhc9zjm`k(bba-A1yUrm^+Wj2f68B)U!nr%hG~Eq3Fwa?bOD`g2pBa8A4tI zZy_dU-Axeb#+9%s+{iOdzuZi75kS!Iz!^df2|mtRWKzEC7g`UJp;D5X%UeNk#Np9w zNK667z(cylWfsG}ZZ$Fstv}ydI>5iiXx0ohxk(XNr>1^NkoM8-w4+XlSn3-VQ; zzqXm3lZYH0oh&Tg#$)0zj=gOEudT=M?Hu`7)pTrP=XTMxR*=#|a@eBo-o$-*r*|CS zPJIx+DBr<~g2q@zWBEhaN>#CMTcILToDc7xdtQ0*A^bF142h1W#wWU?T{lF?uf(O4 zBQdz8K^e7&tv3G;$>x@?N`~GhYf)@TLvKU9JDwevrO9BrJDXs73SH*%9n8ZW-L-m1 z%-WPyZT_g26_c2f6*^l?qRZtZZZ(-3mNf$~goELwxMA-&NgB=+`*N9K4=UMlHlC_- zwxg2Dd7|*RAxH1=q8qov1o`&1$`M5taR zWd_k}HsWW2P;4AWB^BcFe>h+kn#fdHY<85wwv~kVL&Tr+0wyl*1mTr-Q^xusz(--B zj(Faya9VcVzbo-URuYK%*<63;LLn#ru{qqCE9i@*H_j=#huYFF997gNHC!TQiDUOJ zPSXnVdf*QwoDME(MnHZ&fefsCp7*&?h+5wcCIcUMzlTZ$LGI4_5$s;y)8?;50SU1scp);%4$)1CfS%4kcjsS^y>IwLU$1!uyWRpfYmFaKPp?!4 zf?-eRIvqXHUF)L18X}AbU+eq@>)$ZQy&q~XE~C!2&M!0t1%1dn?v5cqF<#s0&UdH-N} zr?{UN7Nyq)-u=FuM6mx8ro5nvNg!;WveVlUAL*`(4Zx72oPOtG1tk8d_W9fV-@ku- z7;#!FdZdxdOo8d?b8$2Y9q+QT7R|ocge#$Mx9u$*G76Z!WCK8^H$)(ZCu5V7cFv8u zw2t$0+U4_mJhibW_ao!pK^5b{bUrnO-z}Eo9`;5JBnf`I4ds<=A@rPR+ENT24hA9P zYE|G{txC{A($G2MGH|frsAcm?AJ})xrw?))*RFazRupP*TK&^>zb$sBNZenN!m;PO z&U>bDnb~RXTHssxDV$aMAxF%SrViBz-Jd2stCd9eIAod6d2czgBBO z+S}Gps7ohv$p4)X?U>`|0iazt-^@EVMNHRSHp$0px=g@$i0M~Ujg(~dAI1^G!(6tH zKI(tx;-i59sWAY9ZP(xRjq<=peGLtU#~O@5a)HaghQrvfs(P7*h9o}#F549b7j#1A zl7e|S7Z_43G@_fD%J7vEfQ);%6UCz&7B?2;tsS8*$rw>dKE0bjyW%PlJf1IObK*LS zcox#}8v|k)QeJHs6#l4ISb9qNeSSUeu-A1~0Ila6R@DUV#p&J{{jF*Qh;=FC)9S$} zT%kHBWM=SqQ))0WQoE1R(5b1Ua5?qa<2kTUI`v?`$MZEd@OX?Pc}i`C?ol)GU$Z@PFrl0#5Gb6E2buq4$rU zQd)VT-gQgw`Ymy!N6nEl_-SeIIih~IvBlmVVz(dl?^jmIIH@4`kUrzWT+&xf8b1z< zJK*lJpZ;n4jmUOjpZZ0Oy=iC7o1!2ajjI-QKqb`sW*_a|#p9Z5A~p`Tk|l+^d$N3m zdwa4<3)sc6sMc#he2ZF#1u=RQ)LEj~hp8}?JId&p3#=4EMIo&WqR478WXJTTvmc(E z*QF|VZu5@joWNt8J&{}Hasf_+f2oS5Ly$m#bv^QhJ3exWK*XY2KRn+_O7IB6-o;IA zARZ^>J%^ES;QKO6AVlZYiZy*F0No9I_LShaO-PsV)8u3w2+0B5ZlW->C_BDJ@u-o9YF77QREX-1{R$1E}Z9WwLVx-sDSkri4lPBt}(Jyj%GjE*n zdYsVnFzy60TRayzI)xCEoDTe@57BM@i98mzUMAs=RhYz}oaHAHPbEPO*rlLajTm_9 ziJPB{ynEfo+1{~=adKOGLb?*%2U`EGDJdzrQKfO#42;579T0`jI%G10m718aHl4ho zlTe|_U*nZ6n{N3&xJQ(WVgKyJIRSfOH`m6dC+&N60b5sahaL(1AE)sfn9+UNXQ=Y= z3UL-N8C$B>?Qms}78P#=V~LePA|uY8@PVuK1d}!Eq2mcP;5`AyzHB7Q{@bP_&}m)T zLQ{Z<_S#$dil@`ep~^zj4fA)c*+Brha3@~+gW{;=rBQC4T%ue?K&ZD>M0v;zGnTV% zqjeIwv*vTqSYzjIx7!EYkCe6L4IoCaUEA4jWU~DHxwL=2Vcww&euE!Cm<=FP{7J#F z*jVovuB%%c`G z8&cZsM9gj{nG$2apcWz;R+iM3J}l^H7{e+PGKX+Yt-?K;jS78RUz?=rj#;^DgdYn{3IT-JyJv~VO(v-X1WVB%<%j5DJT8h>Z zL+9kkXxcZY&0socju3`h>3Y;d!&!glq9z@5Z0vTl>$a7%5b|lQ`dCIjUjPZsYI4XP zXfI-!?!0GK!?cxaGt#dDdCs!I-M!#K=STqxD=g&kk+lRK^P^xAvB}HUfOcGdeA^{( zCH-bQDN`}<%dbO*GLpNytF}>aE8|7&#*ngG(@-PMS>@eyHuihiqRi-z&?Rhkhmc4p_6T4$@jEPq z8b2TI-Iv_IJabAscs|c01VDK`wqJT)4h8OeBwk1YF2{_=2FwF4se099dYz;f5@c2! zM4HVf?Krm72tBxXJx51iS0r-UbRXR5!s7+{bHgh~2NF zfqfE`g1=rOdV=xfjD}j`-;kZ+P6nn!p3d)z7+tn=jE9tvFgII4p3ZOo`JHT-=8B)A z-X2TPVRdZSi%vurB3~hEc$}@V1LRe{|4#tW-*Vr!Yz-xh>G=dcwFJh%3wacNdmdG{ zz^u5n{TWw%##ApK1vRS!j_v55^ZhQYt;zgX&V_bY#<`jRO0_CK)T24^2qcLP zME#ZkO5^+f{H-Lp{N4$}N!UTPasO_Un(4SAN5g8kdnLa-Q(sqEE0%6lC2|g>aZD4I z1PfrVIuITld?N-fx06gdth3xL`q~a)+6Va20)O=2b?_g9L-GT3IU4*W(%Xc*-wl5J zJw)R3^PtQGXn;5@MF!OtI*L|G_MUvPxV%E!+z5XVb=SFnfO;?+%_NxO?Nqq$TpO7h zQQoa>DRik$l;ZPOVYXH|3TZkHZfD7NnPZl&i(+V&LBDG16QN3(rh0fNXx(A`;^l5* z>ujt?mD%~%kI`$wCOcRt3C%eGuT(4!%Qt^w97olRmjR~RZ`Ci5PnRispwzb}P-o=v zIF+r^L+l<^zVAwBvA4ONeLW4bcHbU2WD6ciPauy$vueT8)~qvFJM`EY^Jl8AdEbhP zz+`6-KiE8^PV!7Hd6Gao>yvNr$F9M*w~J-5rv8PaSCkT%%)?7^b(R|uHZzm-nH__9 zrhzLkn_$F^Ts|8xxbm>bmFdT&=MVG0C~O5G8tE{v#7i!)uiaOPhJY9k$N5btgan~u z+@C~vkq%<&6Ga738p>25*By>SQ05l%$JAvDeUd9_AI%{7E!>k#6gOGY`rXM4#wFK; z&bFCd)7NVYx^V-#)cB8uu~#xAfYq$nEKiQ!T;?nKb6RMQ>%2u)nW)JS$C`f2#}Y?8 zmSdsvpWB7~Hj+uJ=m{f&rtquYrK0YzgZxv2iee|dHJgKUD^IYsJ9=HV)#v%<-z5yu zx-##kQ6*@0Zmes{r2yqvhMNID1+ad%_+$I$ArM<1rI^%8{EY`%e`AVWvu^05LUuR( z2Bt#BG-2Y3JpIOwnDerKtAoCMyl!D(e zc8EgE2YWr>;>dM(+IQOS>2_l|A_3<6bi1Vw7<4{Ndy7HjOd4P8-|6t^2`)E5RmDfr+#Am>zL=!rCsM z4^9-zaR{|tEPtsIza_j&P_jeOM%LS|XxZSu6SX!12&gi0u-;7vN!j5@HA1Op4R(In}dYIcK8`^y5`j zJOpv^X$FS`_nTGewGi3?7s44Smw%-t)C`0-ErSBat+>C$NujiHYS&=cNwg^Tcji^* z_s0KA*t}Zi-x!-b0mqLY?OZN#o<4UD+jSwYhpDi(Y-CkWj(rtT6U{4!>S#bCcz@H) z;@y-gN%V_W<}sEM%5P}s8%A8qkT@^oy7rEDRU?0D<)p;Yx!*~6#gKS1e$$Dbzn<~k zHS{+`$sF2K&Vn}XByPlvb*AicNh|M zmJ|QOP+_X7`l_e(ZGlAm0+aiZFP+onH$4ue_KVS{~meq#HjS;^-l{ZAB|1@M+IJJrmzila&opn%&T0U+z{zgiIFUC(Ii23Aqq6B@xGOV8ScQj zpQdi5=t@St1Dvs!UkLOa`R%i^hVycQix1EeMQIg)?{kG&DPpVuBlP3ApH(LkeRowl z{A)tJ-Ad6s2{X1;GaQty51fBUlc+E??iH@2$Faz9{4umjU1T37LYM)dL- zCLpAQ=E|I!ea1(^uCbPNlX_Pjr(%8eG=1pw#m*li+isNePo+1v@Q?86IiAS)X49XZ z@xN=$k-HrH_Z?2ZdYXLnc|XQ!&HVVDmKYh+7~9kc0Wmvd|9ZZVbLAJ%grc3MC&U|| zO3};B{Yk>dD?ilR*Jzd9l(6Y-Lp+v3g5_=nRwahgati@Go*Qwji*!;&+?@;pGkVyu zrUkkAqX*<}x1Nv6>WsmR_`aNqxsdCx)`dJaHipbN?Kp>ZwJugnrsNr`0e2niX}`}l z0wx&zeNWON8mA^)l7P*vei=wM z6A(T9{}J|;QEj%}niQu53GVLh?%q;di%TK6ThQWeZE+7pS}eG`wYZhyZpGbY()XP; z>&#j6o%shpSR}dg?7c7Bw@kVUrjK~In*!_)GascJEe~qv>H<+_%NMBX&)v(^wbfZ} z0yjQpAWSPtT)h{@bsk(8JPRj3s9rydJYBkG*MHgC^zk~tbO><66_Bh!Go)AvF)qvP z8S_*dF7j-+v9cx&USAykV%1X>bZ`H-74#xkiTiMu7?fc8xJCHGd#exvg;#AXE##zp zx$k`mH+`ylVTAQ9ZifxA`pPdWtRtI0D{#VqLz&HS3mj?Qh9j6Cthaj7X^`16XqHSq zraqhVd3fY|o}rQ~7$)s{4NV7#BZb5ISwsmGG2BXrX4OK-ahuDU@aJb|V}iV;(1g=5 zyGEsIhx0Bxl!pwaNG4AH4vA>193?PV*iD!HCV-dZV#93QI(Tps#|qbzI@=xlyX(&; zjfjUBRt=5S=!m)3hzpXjQWuQCIQEG5Z6}D}CCX0?Xj=}LlMIMC8@?KEi;XH0J#ReNqaYrK(`eb)*wX2*hTvzmb03^4`+Mp&=4K8Oq`VE zC}-`9Nie3?pKV*qwOPrWE)1@Lf|5`^Eb-e46vwn-WHh^wVw`S8N$)Iqd>wlyzi`O+ zb^NE?LOEN3!`Jb#-X2@w^dJz!j*4;Ex5m+C)C-?aN0;BG>EyN_*z>|iQS%r&-x!5Ss%!KYlMH+r0}1N)t41F$lRYGD3|twYBpKfIJ4lh zD1x+*S}c2Q5&`+b3z4(4(jH!zg^hk__hI**r_5l3(tV>ZBgIF6^)v`j&$cxU|q7evwrrpi8CEL*rrce8N+YSW? zk=K?ttbV8a!>wlv$L%x@c$R~zYkNRo!wJ>(@qA=^6|9Ri;=T@m z$V9UKl>ii%kGy9Ic}XHZd#I|pV)4sW9dVRxo~j(x+aqG0aL6EzPFSaMn&SOSS+BIC zF3p(IgiUk(WwRADyu7UaH~pFgv-L0+{+z4F^*qu56#+gKUd$ZA+g(~mXLQD6`M3z~ z^&VrpKht<^-D=(C(lG`caP5YN&*s(G28$UbVmS}>BjeS?;y_*w{pjQ3iG*I_Fg2>G zr;^djY*BXcY~=H}<->lC#YgAhU&JWndRlh6vp&q}jDo=%l}9o!CzQ`O{Rb}>PeBp1 zky*1@YXpwH#9*pZ+ztLGqJQb>6a1YsJkUTPd9xx}p6L4Ly=k&iJP}rPP5sdG?+S9Q zev@-#vRcY`&n}n5E8txa!)& zwz|-zU0jP8G-T>T5Hn6WVaLi_XA|w==uvG@aY}ek!I3N?NXqM+ml!@>o5UxqCDXno z{AXjCGY;!k?wKMIU!tTG;eew9Jv*4;=7(iYINk_t+{oC7jDmrH=4W20nHP`s3P0{N zgG#d0_$F{%V=i5sR(>a^oryg4(nDz4-8?5Ro=qe55G?#7`*Y}wEwR23KdvqBIn?DX z$IdGCp^DnzmLbUedJCK`YMGmzBIr1z-IPOdSHUYh7ddje0C1~nV<|z?>8YC8kt?{` ze;G&YX}cAiWlMWJ4?8@6WI-Itn$(<5v<|{G$a=IvpDhsAk8hAd5(yJQ__c@mt3Y%i z^x6e0lXlt0_K&RJu7$@9hoagzkB2u$ztlwlQPfIo$LZiCp+WGw>8|2geCNxH%R|N4Q-f3UAM3k^^aoE@t0nfvrI0tD z8P=~CoztE-Jr^ClQEwQ&CB9yEo33cGpZf4^(W#wWaM@$pZ)#L<^)cA)-&S-+4)I%b zY<%N=zV)+d6SG5$61?cmp+VXHey&-*t#-rs31RtC1GvkuC~FG-jRlc+`>#v%_CoG z4N-45u<1H%CA#5{&ITz#drgiUTh?qcp2?*4l-uS+Y8$a?j@=QAd408_dEM@dUKZ1q z2d9q{JPJ-4} zpU)J#sy@QkD#ELj%*U9*o}10zFBdNZ^p$@Gq0#3vEpEP5T#3Bcs2!+nTR3*DS|MV` z^FQW2C=7ww*EITl_5GW&38QQ`r5E7l#$1g7#zVJzqaQpU-kJ?g>$dl-(%*9xG#9%$#KNS|wx_-GNlmwB{$+Q7WK!x>=SlJTUM>0qvL7xRX%gH8(3({XRp@V6n$ z%5uW7a$p9#3s&aYtntKJ7IxiU`Sjn~3n4rEuj-HtCMoO`6q%TUP3*Ps4M@r+SM(#t z7$ol@%X={%5ca9?hSWf`3z60|G;g#_L&XW)0|oCo^yPIE52S}lTrz2A7iQ!TRxYA@ zAzuV`qPY6Pc4oFixk(C42ro&`on;};4!QXG>%h}l;^vHw1*tsjgF?!uJtV56d_#$l zET>jt%H})o8_K)A!M>9}hOP&L$9C^3tDz7LK!S>eR8?xCD|Cq7FARYJsBoLi8VL8@4M(Vy zGU_|vQn`E>h5B)^Dmd?1H>AztN{374R2mpjRxd7Q4UFZbk&b1{$FbTU^^*`?kl1S1km#@S@FUE&8X~ zm!vqe1O!51(y{gAOs3H*y3gU*(GyU(i*Ij@4_NWxwc^=mgA%owoPAhiMjK` zbGns`#?gT|Lu<>~!5xd)BX_8cY9_#v?2f}w1uE*evAiZay1V(skvQ*-(hu^yJCP2t z&Fym`dE)pfij!@3`Z&JDq>Nl7zlPg{uj$ER;u!9X^yXvaZ_>RL-Ha%e2SP+k%*MVl zrwe)#SgYiQ-_;VBU5^O6EXc3u@|H6QzFyvD^3sOPX(q6M_*uw`eh3P0M$X5vj;9b% zbLItSH`~@gs)rH>+$3dExWiZ=HjWMohFZKL@IbT^k*8m7U`Mrlynq6pI>kbn(Y?4j z2@F*Mwb+C!(7KLmfgfh0CCXwXO^8My6C$O7D< zhZje>!ZBaz4z1ca4Nlt*=0yZ6VjU;{M)ch*$c6X)$NtmKcotgpj3a6B&u;-XAE-Y< zhhB-AQ-J1vSbgk}*=qI25z`3MMD%&=9_SW2`Qx@Wn!%kd-XpFpgc~K5Nc!TA1%-sj zWT@%tM&N;(o6yBv?%Hrjc3f+Hxore808Ff`$!m$~oV0?tD>SS9lu?MBCRKWGk7$dR zur!S{ABHKP0Fn=qFBGO05AJJ>FPF4ypck}6Zix#HMn)8RdiwKBNtfoW$ z05NPvHNEStb9)h+H1SuxObpW67>~&;eHTrmq`eBbQrQrUf7qkvRFWP#eCL8C$?>F; zmqniR?-IvHA0t_ilF_X$xc763Sylb&GP8)jk@B6>{IoNQxTX z&NSI;th1!mI$f~q1&u3@&F~pwK-lG4(;ZIr9@eXDWST@+)N12@MNAkF;@Qa=8j~B? z4NvGA#*N*}c<>WI_|;<@%n(H2UwI(+?x78EFooo*qsn#*usQ$fV{8$rhR{Y>RhY9m zI(66VaInQ+TjX28wI_1`1aBas6LAGQ0v?LALhhGbs`2Dgu+j7YdE)l0ECLL}bic!I zyETKNDY^f#Tu88OB(garjANXEsSu=>AYb{uv?!as9hJ4UWv;2Iq4R+WiHC=WtE4vW z%$b9|xV+*xd*6r!F2{fVl-=p^XeLW2S!*d*MSCMOH#W@u15h%>32$ zi6ev;Sref90Nx=kZh;DAFIi-RiUbhS=@1MLrnGQ8# zZv^bk8vvW#g8pe}>q5MV!?*LQ4)!s3Z(QgXkEe$BG6X?8lLV{m5_*BAJ}t+PaNDMX zYvFW$dSY~Ib{Q6|zVt@a*c~>x{X@L3V{c^kN9L6>MR3uJ$NJ0P@N#=Eh>c{581{&P zl_D#!tvc+!_}Oj6jgpv(vn=Z{)$P!(?&m1h&_5TUv=^FDm(k1Okm>>4xI}Zc?%5=tgdqo=z=lbA17I=M@r%K5nA92KBgD z;+IKrgWV$CsL}?3fq{>aBtcMO6*m{vi9uqqFkhn`*iH5MY@Gm%e*W8~fW)l@UJ&R!8=(@so`dc$~w3Q z=hCH3P&t{n@;C=Pe7xc9fO5$jxI#*Ey5W&)77l{-jm)lsni|b#?A#y4vnjZXS(WgP zo94NThqBS_@cao1GmDw(_V!5=467P&$0>p^yw=+eh9HT|Oaox-RRQx%!hjTSIY(YLa8O`J@Z(9PT3>AznHxbazaC&K%zli( zk^PaV*o?vvx9hBx7Rwv@o({SZO#3>_gaFVEkxjrQ29J!5WA;{<6k2#_wri%cfq$dlIkH}Iha9BWBKD)rUJ~L0x7E` z$nn(K=rA%$L+|8qHIA-aAaPy&cpL%O@&vq$fb7M}O%TSKyOv|HinN^mTrpXiUS_X4 zaXRU*NqxnZaB0aT7PeCC1c>zARCc3f-$M^~dETQ2Ln{835X!)K%1*oVlAhCEIfX0v!A|&y0uTSo5M|u!AEziZ7uvioLZ3OSIVi)L>e45YmE(DN zYSylHl=Cw(Gb4tE_G7KA#ZhI@c=Q9GCv>i+T6|mZM%*)unQHJ0dQ76<8m45Y=r%jMA*q-w!Tu5n>*S$0$tuO#8Fi?}Me@6I*PjM5XBD*S26T z*I(^bILkR(!dwdWF#VBsX}`%XD=dUY6>r(IV$aDzQ7s=gpg{FfL4+I6eqid_Yiapc z_;yZ?{;ag8rK>Vl1Z0^Aa03}!jp#N*X|Y2f0?1F00yYkl1B4in7ynNU$wa-t3C{hu z&3yT9Z3aNY&&$Bbsb{pPvB%t#si?d8%~SOBk6MrcX8GM_oO&Wx%!W8<^UlbN2!kev zNd4kcIdYmEw4EXndv=+5GN(@}TSxpp^d+DF(B@Tygg zVsX}?Kb29?66Rs929FYmot?7aJ-kiMGH((>-~@hjZ6Hm1nsSDSwC7pe=~Ezy{+UW# zOR(C;GFfpS7i%D0jB~QH`|dHgINegS!J9uU@h(0RoPD%a-AvatCb-)R`kAKeK;P98 zH~ooSmytx4ov8}FfMG6TK?>c$s}X7+BF^d8!}t3$YCRK&F@4=mFuuZA`nH>|-eda* z(V86mudS%paxd1aC88QWj~QIzH!ZP?jAUwJc(m1QxY4y#!tU`XuBHAWm-lB{SKAU3I?Y`m}IrcpD(7s+Don4e0<<@u(1ZaJk9+&cX>5Eu1yBI1$brb@{6u)=fYT+PXQAMa_EQ7s z*9v3!_Wp_rLjI|#kYFXb+z-Rz*Y~~L9y7DU@4?H`l4EfL(*JxB{$sI_rR7#)Y;rln zMsG#1=8oDi@xF9lG%77EO$v36L2xf#=SSIS^M2pIwwQ#`_#3Hg`c-2I+>Q~eShJG@ z*oC}7tOjk7VmX=}OEOdiOCmBJOFS_iOENw_Z!wr%&7rq}ans=8)IhB93S1uKfY4C6 z9IS&?)m^DF{-awsi0(X+`r_-b_~Q&)qh#s$16vP(Lru428fT%}-$+5Z5eijrS+Y+$ zBZ}lDZBER!Q>!Q|QSKHS%dcI0hqK_K#?ygyxf{m`+fV20+{WfbX&|aNL3AYBWXUY! z*b5bo-Fi+kxhR@8J=iEfKQ~HmCT-heZ!0|fIy>Iu{s56EL*{hnEqJoT4#;iSK zgLAcp#xnemWp3O0-3X|9ITrj$fm>%mbV5dixml-L$_}7+S<&F>U1i`Fdv;1lU2|-b zfG9rm^yef#D++>lIq_icu^x!1{H^0fvILm=6T_f+?vjAi94Gr}K4c>P93JJnvOm+< zP2at8g3UQN_A)RQ8^#iemU9j9)VKHn?`q z<+5d+uN;H(U1V(>qaZ~RG1vD59(;U-!>b{=Ql!X*+-R2(Sy|k8xWC!W*=!Td-Y63F zRs;gP&4^pe#|_vuZFf5DXbeH0A$Cj^OCSO1)QpjI#aP zP_E21{E3bHJ4JJ??WyxGz}sdy>#s9`fu)qTh;(6kkJUS#`hEF}Oy(x3+-hTQ-7=P$ z>Iv5W3^rKo;)#-8vz4n>-;HR)!Cl4Szr(Id_xGdM_W8 zFmB-Cx48<}aMth5{b~hR=NipqPI|HpGvSX1e;SX7R6+$W^_Q00NHNW^z=V-_&T$`C zh1{Can$zYTKlH7d6|nn`<(P3TchJ7r*O7MvkoU1)HA^`AdThVx^YP=mmyGmfi&|6N zHNb>{X*RYt%U3%pndpSlkQ|h2A`RUwIjdv@e0c%w)E0Hky-!D7Pe4YN>69<;{ROw; zK*@QsfT&O%depS-!XgN^W06Eym_>@b&9@3E!+;b-Fnj!!&6!|+{WsvG83v8YRn+TF z{Q%s|@CDM4y-SoyT+|^1?yYBVGE@xDvXno{N*uVfOxRPi!T`7mn^;`<7~BB20I##> zcwNZ5L)dAKwKnsO_HTb#hWm?uPh|c1nVE2HCdc%H;x{V~wk2YK z5XKJ8b2+Ussx5%9=uLhsLbaUGfbTaE)|>VyW#f#hZVQFfpP@E`CD?X;i18JPR1{{mhNRQHZ9py&d&yCjVO<;^hA8TYF=hYduKqWa9OLfro%Lgi|xI(njhQWgD%* zI2g`=Gz+`ZR;sQ5m{Y-hdDCcVmXGl?DRLP>GD#Yj=OQ|@GpN)^sq9OmKee1tG#XfL zgJsTT6uYjE;7h}A6Z>oZHo9HN_bq4buc;OwU*Mx}GgqQt1*~)nu^OXpUR;cat^jy<6u~_}Vc(v{3ZngE5mVUdPsF%|V{1OKR&w3K?cZMM? zW#u=oD$0;9$^`_Cj^S_5mA_^~oTtVuJm08%*;!V?NZRV!3lUNtbHew;d0S4oEcely z-ps_`w!(M}I?Vfk?bM9*JSSU<5kOF1Jx+xeKm_(;e3$S}pPfRe+^S}TqY6V<0Ufa8 zAbjwf3E5LOOL>mFYX|QNczuXjH4#3asLR>Y?IafxU{mfa?_P((uvv67QtKxteni0B zBPOADzx!d^Vt>o_uPh;!BLMcQSz_e`?}*W<<;8y?cIWaw#~aDv!AA#;OW!ZieI3h= z9l86K&S}Ka=q1A0K5}C>Y$o_a#Esdfzy~w=`&&Lez2Sfhh|V_ZjPK->K6`<&qA^Ab z$?zm)g|r%*1aH-}Y5bT}PId+1_iqYK9RwB0a4ie8dxro^X!9$C$)qLRDoK)VGiA8Y zBNZaMM2pf21lnq%)cX2-$+@V4QcCf4Uk|y1Z8*QfuYZs2Kb8L?PcRE>We?~WjK}Hl z%zEg5IexY@^b%8|_k^Y!Xvg1Bz8vFeKdW3}TnjvybsA_v=W>23E`gd)*Uq(_y$5#S z8VZO_uf*7aI@n&Jhh^ZVWBh5Z?+^Qz%AF-T2MH z%&}ao-+AV_Ev$MP<*aTpq?#BCuQSIe(K;EJa=}(DXoIoj9(NtE+^cjIgVV*q>NA zB(&>NGE_fK6U26s5BiFaP|b9o*}E58Um&;?nycQ3dLpl;h4-`$h5r7iS}?76vp&P! z4$6gD@bk|$_5Ll&=>M%KySbOooo->4w*;}~`kiw^?>{e|EiG`a-&MdOhY{>^HCDI+ z&MR>$Sq)~J5f%Ds6{{R|T6UY6qjNQ`X)~2ah~#pZuG?BE!z8?bYw$Nk{nqF($Vez-Aguk#$et>GD@ zw!tQKOl`y8yUr0T2_;IN3yrE1i`yAf?0YInvM0C`o~G~H{5j^7hi{!l`t+m*ImsQI z?A&;B$q_)Ne0)b12Z`gTLQ+jb!)$%uv>{GlwUb{()k!9y*6h;>%h0{&1g)v+7bBkW z8FExxEi>0@_~WwCV3m==lwBSIdh>yq#iCC;?|PRqK671EW^sY`E7Ap@1V%DMDbWe& zXlo|Zqyn@bpMDapG>+Yn?ECU*E7g_oEHhc zu^Wa7IQH+vFK#SA#VhL%s@*TV%KdL$%fbFR*?$J5C4$(_5r<(q+mxoJlyY}2s|4@( z+cnGR6A)uxC~$8ulCT^T4j+?0`CZPB;>-wVOW>u+X&5#VU12D%VX@0IJ)-H8sm>XLX`DsHOd_+vX&~3N z>AX7}1&Jp-h2sF^VTmh%#9f!yR%RP?VH5ic%1Pg1T#0tb`uSV;oIUzO6{W3RF{_9X+ZksQD3I%)<#!?-dqH9uZ4ucn{dYMve`b^9i!adiyXhkQhu7CiLI@M*p>WHTfhIbeZ%|0saV^zgIE; zN(ukcz%Kvo+2yHqOUg0t8c11$UYvoT*U#~D9d?Ad^Y>y6j!OybSpt@ZAzls(Avsx% z8-GR@Pe)RZ<{F&%P3Erfyc~gl8V_+K0Y@8yg=oa@GoYfY4?GGLSdEneBem~Gp^IVc z)MfGjvvhSMUwx zO9|u7KCc$@{9mhy)sbY)I`__c8WuHFEyj@_2%7(ni1)GHR1j+g(@J!LadTHYUL8o> zpw3qLlab~cMZ%jFKuK2HLLckua6IeHb484GDHO~begvaGh`u6|UXrt2i7zMU z={E9d^O|{J1^%&-DXo1KJZ2Eqa-d;gzyjKIJ?(2@fhq#yR6blR|FFF2`Lo8e$|fw! z#<)ngpN93BJ6BCNffe%tuwi^NGo0b6>nzf?eYZy%2!A71_exo!8hKc<`IYQ2g`D{t zdLxRGu+O^aY1n1N;r8k9%fS)XX0i$YmCxmPfjWMzHy(%8;>+WV|v6XWUUgyhN}<#wwU}Hk%F4h4+c9 zkSKd`{rYyRaP)oI3N8IgC7Ml=2eJ54eon|EPg zl|AQ50w-eR-V}W@yQGpyoQ*3!WNspx0T(4EG8kEIy|lO-OwW#>Pi7dG{KE}^?%mXk z^;E5T874aUYbG*vf#Nc}WpaKlDp;TW-jHQt(IEVS@n&O*SsWIBK2Z1%s$3n1niGil zodRQn(|k1S8WQux21lRu3)6v?UxrZ6X!6w=dv&u)%?fZ z#*>e-k5t(|ic@E|S;lRWB6*Z1tg46R-G>zjdO3`+ZhYMzzLpCRPVv^PUEu#HDw@v_ zp33>L^T0gzv39N;+5|Wi)GGi}eQcR!;q%}tsAT^bv%!Lhf}(zPM$NY(9z|9QL=w}` z1JsRlL_2nnx~>ZKz~c9;peol{qe^O&6$sCk!E0;`3|gE&GFAcN27ame99$v$_pf|j zvn1Q<3l)sAG9MF{=3CJ;6`4Y^(j#uNN0m@B2j_#l7#$Q)+z7X*>~#g=F4(x(U8wyM zptifzq!wIu@u8Z+xLTLALyq25j<=WxOiYszL&3tXEP#$PO3p;C)o1lGn{aQP8ShyYEP|tCIuu(FW^VlERo-)X2 zEI;F)^Nrz3;C*Zf+UC-p8cv6Q?HO=DJn(^!Orerl5Z;Ve0#anaDjGRyPy=yJa_$d_VwYKG^wsA zjE5Lea6Q3(#$gPQ?)Y9;wvm(bJ@^^Y(y~GI0Jz?G?zr1UZZf-m7cE9)(iZLss>)s@E^^~MYTk6j(g>fA zIOZI=b@I-FzO^lPG!IFfo6FX~*$cu%I#Bu~NFPi#NxyJu^ujH7{p=Y1tI59Cf6sk0G%2^#g5yE;7$9?72(;{^51k_~2g9wIS7^9=wcH z6?IS-(}s2_7qmgm=#_;=Ad7h}?u8fA@%f~taAY@FoKtb9KbYOPM@)yHM{N5=wI;po z94=0(g0#ZZ$zukuu)YZq;TOgpN11}DZKyiA@7uEQ?-Pa^vB4~o5&N`6wl>k6Wf)#> z^95&S;`*zxQ@tX%W`Htk%6KqLbJ-ZiH8B;^O$6GzGW(iQd)YFv>nvYo+85ssg_Phc zx4_%jvdH*-g)d2fh3r53j{nb)24-a4BB@c=(1;k9aFG-!H%Z*}5{pzR`zt49RiAbL znrpU0&oyYrA9q>`HzsYQ78KVS`*aSLyv5k7uXJ|R#Vf#Ae`6jP90tB&>m;?3@5dP; z^E)&2Ijedh#SC~Ly>0D$bpJwlXNLEb;@5chTH^MZu{(J(#$S)R98q+PXJ$rDU3d25 z&=3P2qO$suF-n!Xs~>_JIkFF#S4M(o?vI^T;HqiuysvqNqdx-)C<}>Z8MSdK-sJ(c zCnpxTryp`I#Ti0QsR(ssh8Xv9&96SZqDuP|;)y4n^PLyvvmNy3L7z)Y8>mxV*|_;6 zSB#HV7^V3q@)mtoa@q%(`cm)kU-6o;==7LaugQ;@I2ZL<`Nr~m+H~pL>?h0%pb(vP?yk-9ws_jj?c4o*+=ZUyWj-3pde&c(s~BAc z2NrI2`$LPeh&w+s)nWvLoqycSy5}9m%&)ub{m#^0PGui22PM0mpSLNicROE#Zf8xO zkUFmQf}*G3vB)4*ne1R3nM7FKjg3^pYeJv=-GN6wIvjqiptj4n=Bd|Z;Z<1N3iJ%6 zp1F)v|Fsi2>6kEXgO9*8CXo$0<>a3|-5K(2i4bE4qfd6>lMXVL`J~-@gFrjeko!3t zzB+$0&+1m-pAM8?-CleO3uf-SYBm>kHe#ilaJ-_ThGRdr`13krJ`*KY#_|#$iQ)f# zRVLlXEwavg_tnl(Li@dVX&qR7{jy-LKf_JzNdR+uZj7RpSfxIEFHR?)*C3)piN7V& zZbDZpJYwptaA6|X_%Yrp-x=&KMDhFhszIOm_%JZ$OiD`rD5aD#7}Zf8=#hrVA=M_b zK3mwil-NB47hy+3REYs|gle0@SR)ljqEq+IHmV3q45B|aQbB%jj+591GCDTszag|n zk*WpHO1KIZz&JUGTTpu-HAN*i5w3t?uZ`n(99L4h5m8<*{eSofssG4FfX~Uf(%sfB zz)7h!*oL!?T@fjXo3Wx^YkxfL&z4%)=Wgd%wDD8BzGOvy`GWT)Evk( z(#DiufJR!%VMU68PtSwZP0sYGn390jdMQBm2vhV-zL;iYrVYZ-lMa_C+M-+zJA<&j zgG|VVTF_op)NL7+1Zyrig+d=}d+O zFugoc$yX}!7sf6*uEaB3bBYt;;e?k>s$)XQlsU^A$PbN=JbGw$hZ5S+53dW{yq_t% z#ENf(R8a5HCrPepX3gY5`Pj?PuP;$ZCXA+|a6tZExufQ3!@g)2sMyouqgFvGeA44uZXc%-K0x4zrb(Mb$mz(%$&Br1)CbP9xYWK#KN8cgmw z%Q{=4`#uI<%G+^Im_+8zQZ3K`>%vGUfsS%|Gl`W^P#}ic8)blUmLWHe!+@DklxmQ8 z3&Pc2BGSaHcI>e}u4?=-ey8OXkKzAFHCd6?uCboJRnprUPI~~0H(KG&N_bG_n%ofO zuGA5ymOIQj5;S*aC^IqBzaKMdCcvbcXzAz|-$C`>!cpWdT`M1#eYl2+(l5_dk^_lB zx5kHe_p9p%K^LZHM^%sB>29@auFY1NhlfjOjvaYChAI|oA9|%$5%%oB*vl1I=1niJ z^hZ>i#A(D<(PM|{)eehLW8(yHn;LT#ea)}u{IEd+nQ;Qb_VFi7=D9x|A|-`BDqSGh z{PBmIY#5xtGl`z99MmwFrol>C%MCS36-|Z>z)0IO^)0(*nixFb3hO(Tq>>F+XK5KV zc+(JNVZ-tLkH3!ABrYDwH&qkITbbAC3Kq7P() zNn7$#geQuMfYQx|6eVM_Iob8Pj3lZC@wXt<6WL%wjA!0-xA8Jw|9{3_=0@`72(hhQ z!k$l{2t7c^Z}EGojwVZt1_@WnhDuXTwTf*A$U9j903xzP6^wNe9-e@uY~F-{vvcHq zWR(=9{4XcWA7Pt8F(mJTBzvj?&pXcwU#`R-Z%qTE8cih8Tj%LE!0R49+iz-c=lvzE zZiJHTJC>mX&sDf(IC>=ji?(5252KjOfo+@DftWhK68{Q1y52?E(e~WCL-akk^KDa~ zs8pkVzn(eE4Sgfic4i)J+eAq|{1ew!*gfG$QC)FjV7ofZrynyh+gNY^E+AdeRZ=>Z zAEh7(YZS-|2{!T=Y_lmFR#da(H(=e@aB%Ih=IT$IZ;>-Nwq91hRhRxQ>%v9s-RpYrF!8>EntSSD=kTK1Qf#h5pipqBj&dU>zAyKVWVG z`bxo=_%Gjp_aFKyEb_FFmYD)$#C~c?R}2`j88!gCBGDBVe@W&`AM~=9jZ)ozdKKO; zF!O*8Oh}=b(u}e(d}YuY!|?9HX^YE8V~-<}e>^(kJDlBHdksVFa3wIU0ZZnDrb+0I zT|tCM9U{pj$@=*`QAeR}ZPoOoU)5{DYXw@-#vDV3IZJf51wkZ z<$pegc^pak87F}*N8aw;I*X=G6b0Ezn72@aguP-IAElhE3zjd8oCZX)Vi6dMj5KKL zliT7Jg9SIvjVQ?a=Gig$>ut(Q6|}(gnXGmb2D+hR`vxArenASq8RWiOT!zI?ttEXe zsR4bEp7{L6W{ullKe#wbj%=NzO+ko6wF5xLQKk_b?hPnP$S*)j35( z_qpZ><}_RWg1~N{^IR<>*59}Cp8+b&DcmvQl}4s6RKXAz{i-)ve03n# z`9*w1$P>?N8l{slclL@su~mxWXT#!>i;$7qdk248PPOs&OP&SgpAN&p!}h^Hv%~lI zE%p-5e?Kik^W1Kmh(YuIvrs>mogWl!x027Ss+247 z{`S{lwsmzJdSTvYvMf!6lxqE+Z<=(>r>aNRmYR=6_!9utR-i zF_|ju5=CqhhH9Gpan>Mi&=F?slA<$&@8qo)7EE-HLndWo5cMa(YRRU z_c-8E*NRVGU}3W@#b)W<7~qLRWygAe@@;i}f|3vSgv$i7VJL9T5J?3ERAkrx-c2l9 zJ?a10sofM$Xl`O!2UK3LB#J`jnj(=7;tM<0#|8~3xbAFe{Ey(_pQl>_PWHeqCUowW z0<4=ps=$1lqIl*Dd$F)fq)ENXl$9=ZJ_9LY(Q>FI4a$bMO~8&GWy;*@h9SxKGHex` zU7rSI*ml^&3W~Tn2^7gSm9t`9yp;=2H*pLleM!o=rpUTn%3sM=+W{0kDwUMRMnv5;|Bp@L|6$r@r!QMZZk>KrvWWD#ACNd6 z3tOJh)J_4GgjFK;iW@~l_AoHnyQU)o{rG161_$CpOu{&U-~WE;bz@O5{W_8e32L?W zdOEQT*TU_v|Va+;gzVF_88g*yPkKUnyjsSF^444$4ZD zqwa1VD^aH^qI2V%Sui>Dn$5%{@5r#(+ID@~;kuW-+OuODRQJG^t)>8>DGBbhuyh9{ufTOC10(+BRK3+RFR_e{HMSk<^|N%{Hg3qy@ceB<~*mUG7)jDmI>X740a3{PzQ`OrAL zyZm-uW1I3sZQ1vrg0O0km3y?PuR-(oki>!5N+M)Adfx|@1vLgxQeLZirte8;I2@c= zy{YRz?en^QI?ZxR9>xzl5j%?V=H2N~iElUu?8%YMgxq6&-8}Z*HS8f97M}l3d9m%p$1% zMx+k*-n?U&6(mTX++}V_^E?-B;<>w5tnn8n<4pkH1rzet%D%%r zUG?kZaP%*;(>IkA60t74t`^!LIERRv$$C!&V|L;ziwsSWGIgC_Gr;V#Tx6K$P~iyJ z*6F8Yh09303ChxbDX2-VhbSIup(t4@SC!yINQarIZwNaqyw%IhJt5&vg9+PH*0H@K zgsRSaQOe5Ao0xCjhDtK9ns}q7X(qFLVQ>d@p=04rz!~nkWr_cEUO12@tbyBK@hc~3A|yB+6gh2!NckOj*sl;a}n2Sd>Y zlM3GM(N_mGyy8dPBW6h$;TmmWM8BOz*cdIq$O8<9HM1%ZV@iPu} z_P;)>zvBSk$b(B+8%@ObeO<&%Uk$B!__X%d;kn4#_~GmIy4~BC-R3t@O_+Bh%>1xx zG8W@x7=#?WsCVUod-EUKBw_ZlFIrzhx4ARrOuc-~sxy*Lsv-RP!Idt|5%70JXxokT6kr{;c7^sNngdlxeF{yN25<+H>ghc5oRrt zg^jBbO>MeNQv4SAKNH8)rFz<))gz-8L%VITA{JX+eJ`=cvW1w;SH4-IxIQ?Z&5OI~ z=1y$)i1mbePs!OzIFMi&57_$~(yie3v}uU~N9a}<2Xx>-5ZEdiPL0jY3ozrDlI5)& z9P?T3Tei+AxwDlDo6laQXV>^mZ!eX#EuN!2H8V>`zJz>w8&~*o$p>~+(VFYu$u{#A zDOtyAv>R{>$Wu_0QwCPuBaX-$gWkdZ^+WaKGHeK$w3+>9alit>f7#p(TY&Sor=Rpz zM7S{8kr-eDZm8Ez6stL-cuZ02`$w4?eit%zzLxMt%k~-%pZE3>A{TI_>=el0G3Vax z9-8-cYlaboWWAM0>4R>Q{23K4E|e0H_!Ny8$pdb3Br%gZ2R-UgxIB{6LQbQP>(_5D z>r)E5>ao`q1Y1ashyc68LbTnQY_{Kf&duOh;n{CJF5pu6P{Kl7&-xairm&BLQm^A3LtyT8lw}ZGJdHZ ztLaE&a#9jV02aFxf1R0`X=G_>$(Wj9_8ONJ23iT#(@SnC(Jh9`;9yKwslusS$Tkv-<(SH^c; z0ILO8l*6xSz4~6>v+|@CXQnHc4`K1JJP5V~Nw(sHFte4QxFFq?fE1hh8(w|*3u{d1 z4eM)kXFM09s4@*V{;Y)!{%LLkceVR_u(kEP@z)F2?A0gk+JJSKx9bO(lfsP2UiUy| zomlV$h-`l-SMD@e0(W@0?9ta?w3|JJ(fUug6KelIJQM#}#JkzCtc5n3awZp4HgWv? zVtC3bZ)i!Ql37JYe-@VVZOh>4hGttcjb8T2OYk0kA5RN*NGp+2$G3Y?ahA01UEVN3 zdKdeGyl14sg1+pI85!uFftPHLvLz_%&NTng^pf}Qr9XNcPKL2-Gc*}L*1M3|G4JsW zHLWO`m^6jbrB>#k3=22r=)EcGdB4C5mLLSLbOYI6TtLl3UJzm|2 zPOmT3Rxv|fxeA>DG7~)RLKvEI-;KKiE4P@|^^zUdk_0j&-58vPvZAJa*W$NjGvtGl z0b!qFaKm_xtgndHS!*s}^C_?*V6O?8$&!EhnUEsdTad#B!_%FIm7%L5yHB^cs5oW_ zGUs{=rQ1D3UX$lhW$=&cPdivQk;j2Q*f%ZjGdWQ5~s*AA-?^=F;<&T3b|Dr%$ zh$+Ll0Bf{&`DY#M$;kF!t#Ax9(~=mo)cpN;NwLc%_8_ndNslvF&1Zp-J=<+XfT5n1nM^X-M)Q$RidQ*xfNP!;*GZnq?kPowFKCRgxzKo zQPn!c&ry_2z?D!w$>>$Yoequ%|8wH9!TmoAh|PL*^;OKj`ovrJ>sAF1=L>Tp^3XT@ z!sLbb+R0#Ne@jI?RN-NyL_^PI25qNwts9=dE9sg^GGnUK1x8vl%z`+?$3V+ZL5p=l zi*4{1CF?U8nSA~BUul&ymICB^7BlkhlIWG#fO2q)br}Zsbp>IwU*$Ef)w@`+Rp~@4RlEbCXG$z&}e=^#eC9RWL+Ej=~Qw1uTN4U zbwI|)q+d-Gip`f#L=UnS6xQ zoP(1}D+l?qCaV3Ko$?Stj;>4+Y|nWOvR(}We5#eAV^j<^EkcFm?c~l+Z7TxI4osOh zd*vh)ZBmhY>^87;XwI+VLnpcOF@`Hs%P9`Rw?~dLS1ySj7`L=2Z)U`9Z=(>;_JFt; zWFiw*2!V3UqNFkyulSF3kAu%8I2#^Z(Of+AD3voTzq4U(VnT@M^%dhZC*eeA>(xe(g2<@zN^Ib7MurZjm;EZW-|guLoa6_H8LK>R8=O z6V*yYLrn4I>`@bg(2GC429=yV?20nJ?(IzDdud<<*1bf(Sz9DASKPnJ+DYED@t+}v zM98?1g5>RFBZEIiT1nb{$^ser-N8lb;aWX>dDn74!GzH1z^Wd*8aX-vjunlu$j{R%6`#4)j;)1x!lCv0U z!!&d%s2^htGGFkVNZhovO^blnx$Bf{mCh)y_PC`|j#W4-mtr1*9D{z&_bXjlGMY-K zQueq_7^Wg%W;ewn$%ZZarSUV6&2Gv6QgP_t#!M3G2mf7 z81kw=GJx(I%Tg^}C(Iwc?bos5g??Vm9sKT=WnxR89*$dhI^y>?jgO)ayPN_#dt}m1 z@h+lLe!0>Tc(Mwa5zKv-nft&u6BG*enXbkPF2_ZD>me@bdhkQ$Ui1O z8~f|t^4bh|ZUXVnf-@#E)Pju#ZSV|FZ3zmBNiTrZGKJP~9DN}foit5oa-D92EJsAlU#y*%v;S)&eh()Bfh|;m+uNVq0}p22*wybqOZcO z%A6LzLOuu2C1 zXSM|3)uj~Z%~`*Uruit^kEeh2Tgm09P)04DfJ4N2Iq$9#zof(W_tfvqa-Yl9*nDzR z3waTJha;WUsgUVj7Kp~o`|-=ZNH2S$U44b5m?PnzCI zFEsf`?fuBkp0j$^1smJqE-G%M^{%NSHsy>$NUMg6FS~A0ozo}odKujLtPZ`IfQoUG zqQOg4a{9_W{5-mo83kSO!BGBOybjPyBoL`%)q^g$@<-3|qhF&G45B1<+%+;j5#B!X zwXIzLNz-|&Xc6cnMTHI%ZUu7Giq|gr2U0zEQTB8ujZ(a`vG=*-{X~e+Ccm0prN+=7 ziD%AnQvKc8>-s(E^X#+X-cB4#*@W=AwLVxwPNp=+5bvM-lYr$UVaY;$6$PRw(sc}h z+-gZ4@uNizE-{XK0&yjH9ZpsLJdZ&GDaN8o}2OLwq77t6&LSm_BQ6abmO zeZ8oDi#t_sRV{tVZ*w?=?C~iFzkJAx%i@ExANN(r$4V8~T(Zx=>|IQDtNQZM!u6lH z=*NDbt|CRo4zj48q&_G) zOVdsi9rh9HR;Iwkk#lx!t7-5E%%(9X%iC2`Q8O)ex4-_m6EYGGe6w|`_-`iue?*%6 z?`8Maz+&-(1knafB~`gsCij)hhwrP)@9(bkFyGfs6MEzU7^ttPH?!l~GUYkj?*Wu13g^f={j04|yQ3 zi*F?I;8+$1V`pDuGhwhAr4hk+18 zINm%%?~SU%6^Rn8xWt{kv#^>fuyBuCo9B^v=xd27(rA|t3kEYEb1yGLT&?~}$Bd$O z3wFw+jED7ZJ!s&&axwmLYc}>wJm&;x{z`0O#6IE25Smx=&Bk93BrYcSJAHFa4@*)@ zcikBFnjbUu&%d))g5(}MM7jp*hr={ii;#C#1gwtC4@}|A2v>S{CuSzZ65SHpN`*ou z@>S+_i&<#AhZd{5gc1Z(RB`@byL0^`lKN4zUnbvJod@&Kp^>|2+Pfto9*+@N>*#yFOOcVbpG8IZ6XTfPLFY19feCvAbCFJ$zak5yIqK(^T zRv`>;rk??x@>Jf|s(QayPkM>w@l`0<~oB7`lw4F3I|kH(3Z1HYgh2(aoF_$U`YgjjC9flrhYmMz@C^S zOF%#tuly@emrk>@rQ0%4i;x9aO6%`>}vPL<@yU_xE;aefHV=Rn=`Sb_a4so(PV-4Brg zfy0O84XYARR&jQZisNUw^msL{C(`no7Z_JvW(E}IbP2caOTT<+myz$P z@`RhRCQh_!75CMmXK_Z4iaOScFi6YC^^;jjrkj_qDyFD(uV{F8rTo@h#Y`^iO96f^$tZU@T8~ra7S{BYJWti-Tp?GCb1E{9K7UxqwWtTx1spG z;_x&f%15@;pRU76Q2CE4W$k*9y*1b8^zN;yho33SDz$J$bCSJ2*MwixT0svF}iAONLWx_xyzu%Ss+mkBkS`_QX66~QB?$()kY{5HEJBJ1=956jo5d5O*4uP@uI8)XAC`xY665kXSH$!& zrU%n)<+>KcX&*d#YxlDbOma=zP3+@5)YAW&N|7crp9vPnF#0zZMs3#Eel~0gbEa#OnrTjQD=mYJQ+@wob*CdT^2^Yxz*QZT%p4ZLmH% zt~@76J6y8xeL!Yxc}0195Tl7afM{k=Ub)12Z)%!Ek{s(R9pCOHYJH_AnTxE@~fUk&Z zCggo>y5E$rIw15_8-y94fX|ftTuuS&i`1=tN6}7=HwBnjSmR}PC7^%M$n-1*eCPY~ z=;n~#!e_yGWKKGIJ|E_?w;S`zIcgdjp`yyqS-CvzGu+&mt8Sq=RnpyhO8Q_~88L#0 zvXHb-uMPeUWuCtMt1r_I&)A3gkl}Y%#&X24$^9SAt3n18X1>1SZ_`sL3YnN_*QP;f zZef|iC*03uWhzpGAG5r1Vv5#rs!-sT=9`TMGAr*7WZhe42zb;qNc#aRRMLn)W-9?&ufTypJbc=M2&bm;0Lm3j8q@Gb?pBo8p(IX7h zB5$D%;}1?DH$EU$F|pQqJ!%TA&qu>`8&xt?N;}<%o&pm+K_k52{0xn0aahrmS$Mn^l{mEI4^c3!tvq0|9ZW&EO(vI*Dk=nj^geREc= zFP0>t|7BGYXv~;a9%Pivyz&@u)B5>lchGI(owrH&Y6NX`LbOGTGqS#DtEU!h{Zn&w z(5G52X}G?8aNIY4+}Hl8*3S=NLfQ_wCe3A+bOw%0Rhf)EUZw%(5_W4n;s@P!O`yWi zwJx_AGuW!cGx+w_*1eA~Rxw3fd3pK!17^fudwC;r!MZ&h@^7Apsa;H+N1(n{l6G_X zr_GXv2lh|@eg^Ow?8lkkSrPCHyI?~-l8GNpP)UlruC4M1q6fBn|GGxt;eV&k;gQBu zx##8OhDIi!uVcLFbBB5O6nEJgR09=xtDkl+_H-#_;5mo=sVAkb7=O+1UAHT!lIc{612^Gcrx-#*zj+o?+`t4 zi8@H(>@sCp1rC~uOHu`zM~_ussVb}X<$t^+lbt&Dn?@3{Ct))U>ovL1r-Giv#?boV z#*kvd#~}eAV<|G{43a9>^phlP@XRwiGl`xJO{NUe0TcL!IOn+-C+x$?zz1y?vWU}p zD#0HjD2^2;G2BsFp*B@4rJu zd<1oJRHBH<7f#D`P)Lgx!9f*-M0sjdu>tOn21|POp0X{4< zkO*^RQ+n_dS?-aE^vK^*$({raTr8c~F%sEx1LAWXUBdVEA^^Vvz~=vu^I#ttA4BV% z?(@HhrQ3E>5u)K|uA6Q9Xg&9ZHU_<5fe@tDl+c-%tgOK|Jlu|h*Ym4iN~TXIi$TQ- zbg7Iy+92Xj^C20p<t%n#$@Q+HgGeb7PvdaWPZb;S_YTQY#_n(z~?0TR6 zro~#UbeJ|k=s=NGk%CV_iqYB$I=t~}b|V_Q{PvZl$oDVI&<39v+N63X_P=9YfFY`k$<;u~)0xDCJNt$Dg z7yYe!IzUVCa@QXDR1fQxYCHJYXe3cN&gdi_tlv`vuq1Ddmwk&km*Vgx3F)FaTFe7z zBgj3djM=-%nE#_h5^Zc(=tMifZP4`djnO4f23wHz!y1-g0H0L!p@9wqLbvJeYTjI-^L@kl)Ex8xFg7ilk0r9=^D zBZxYz34BwW-NqEs0NJerfq2v%ttTQT{Vb(sim(a-7?`Zf!rqBCX^&Uh>)=gqGwv#Z z^E#oF$d^K2BLi~id%ATw(9Benqs9|ztJoKv&l ztUE!mv%HvR%&63ufK0CfaF>4>;>W2Me;ZIQn$kwx`-DyZKMXx`N9r~MOsFIM=G=1U zyiRiJ0PPsKq(8A#CX85o{Yl^9SC@X?$XdkYa`f<0#OxY+xknrN&~ovw_i$bOuC26B z)^c!Xe1MllHy$8nJ#w6icAbCC24s**aWHh!TKO&ocymg+0r9I>FR?41v(!Uns8%~> z-RYyYe$afY4A@kB0Iqjnj!A!G?{(JuZe2vv_=H?N_K)VX4cmI5Hj>0j2e6w|r@#;D zVsHCRKVRj&=(YF3Yr;k={?&cM`0K5w0^VFh1hB>ahGdes!Sj3iE&V)s=CM|ipomP79j7*|I@{m2SP1?b`&ts^PsC6u5~nm#O+nElufGsy+DE%G^g#a2l@>#H-hnAyP@2r=0=CHuzHWv`0X3 z;d6HYGVR75@T)^+))Z0P`FA{iz&JvZK_%Gw`bUdsnP^C~tkyu3!Q&#R0w#SghoAK- zL+_UGTBm}mc`iRt<*aOMgjZ@rl1h{rwz~ofJR-p}`bUmW8>Dv)1lh3~Rzd{Z!wS1e;VM_O#4`zVpp7FHey!?f^iHv7fT9F*o)k<5>)C@ z>VBy_?Zh?_e^N=iB2IB3heZcBbk@6$J-f1eF#~Khwn%VypT`L z?IBQDuKsW!&>+^cj%nhzq0Ts2JEN5eK70je0xRN`-%qS+|KIx>QCmphA$wp*SJdgU z-EK!+coT=+`Pg7!&@64>i?I(=ZBDd;p}bx!-CSY_?2BBBnq`h}oJ=RC*?nvNyvc z5Zgxb5b#V7*YsP0x~@0Y!M83wcwFo*1?mxVQ3lSUNiQhpL`W3=oYpE+h|6XaH-1dH zSk+B&E)XKjbb9c9{XVxdl=yw|pxQ*FU&aq0UJv^k`pyuokj@{)wr{1ow++Z&3XgSDB){6Guqthsxh7-PwriwQ*(2r1B?G0`sWQ`Ug zWFcRp_M)-?>%1NV&~@V$vl9^Cl)=G9Z!kX1Doy16(_ggjt8?k<^V@gY(Xik##7R;K z@|Fh`m^!8!NE!w4jYAiTgfUAJym)ti7qB0@#?Ts#ruAFhqCc-_8$JaY59dq{Ag+&q z77(nTkQdvL0EEO3i924q--g8=Z)&Ey3ak#-g6*2375%1<2Q*c9lq77&h;iIH#xQ4Q zxUMqB3uAsA?L}x3e^&Er1F))J;a4u((o2^zxfr=WYx0G!%SF3q1(!!Ni-HbB8F`e> z*sXS*k5cqJtV9KglwTeh1HukE<&T`R>BA`RGZ52|+j-e#1~T+r03hs0qq&-1Fu6KY zuoNjaZ^)#aP20PTgH30qc?Yt`ZhU|I#1_mwAQ9(@zf!IM$ScCib;ju<;6Ah$E5Tpt zUs(MA58(d({)k_$YL+%)$hmXb%GqmK1>789XyC@v*68~{=^|dgaNL;x1T3-2wCeL1 ztuWNEeE$Z}@_+6Qow0uHvVHMzMgtkAZT&B;tr*T&ej=*ru|gAFh+XvDik&s(KH)rq zCocM5+}H8t?YY&)qA;6FA!Ds4Q1~-4DaT!mlp)Hbj?65U(W#lKr8yDm%ZSdkyXU;* z4c2C@?{TAuULgn=djIWcK$h&Ll42lBoZz2%aO9J^x3UlDWp9f^wdkYfQ>-m~AIa`| zyPy>h_%pB3N^s7P7S39oL;!*4|0zX=s-14YxMX?=DXEK=j#Nm%x~~sp2|G`WqVkgK z_EYE@wF%+$OfV ztBA(Nb5{ef3$w*gPfDIYnkr{GvWSOyNa?TagU(;{Ic%|8V zq1+V+{J1sf)*w3jeyPRj;s-}Mmd3V5K}b}Eg`06(TfUMNt6Q2O!-H6Llq-gQgICSG z_ogc~4mfjXMw~qWe?Kk%wb|<@7(RjUwg`iv!s>g1YCJ4B=IcaDj~y&sV>hRg2T;3% zwLeg2)ry;(i9Nq1XJfrxO8~#%nI%b_BNO&<_)pA{V-SE*U^~Faq4N?+z$>lwo|l3D zvhlZ-fL7!?PBj1iRnO2w?niVggt_mtE;8O6ODs;d6J6sbPj^MH)lRRB=5C%g-UwW( zM^hR>F6j3w7M3C5y!|{kVTpD(mnC<17z;umBw+&RaGcfUa>-4y-L=tNqSpjLJM8Q= z05lQ(owd6LwO{?zS8prOIVB1^UqLMnA#~C4jhddMmiMgx~aQZq`1S1~PRb=6+| z3LkZKRfm!u3T3@ds?215jN&8y!mL4dDYLlty_s(8mx~0BbOAFwz~fQ~xn;W?-*CjE z94P;`7o1?P(kY83;hi@Y1ezYoXevQ~P&h5D$jglkiDpeX)GbxvM+Y|vBDFN% zs&W-9Q#ynSc*GiU4*FWK(OYbiUE+Q>s8JKFyKyTB}(|bo;v;wbK~lDiS_=e_Ic744ZK}V@4dfW=|#!%Y^8g zKpbu0!+~@QnoadxrvPSNTUDp<F+ERVbMlX?^RfLzJ9S!q<6)c*nx3NC|e%@FU;GGal)sf$xPh z0Xg#iRO|Yjoq*1Bl}z*W=kWfO^zh;*X}!lA4*?zoJL$~X$jN!tr@4>$Cf0IxZkWUo zLbeck#nk4zRyuOv))sEJ-DGm}pCa?08kvO-%0a17{q*;H?ZV6p(dplKkyQ8PbwTz% zpndq^>W%bD+@cE>LzdsM_o zV%daz-U^WnEKffjWPmTK+kR&Ho$a$!pVf^ExVx~eW~L$4kA1!vK;OCbAhxQW#VL_M z;frKge+|7}ETdHLW%uw)8r)hw1FmFHV{82Eaq|N*=9j|iho5jY8$+)jXMUraE|dLn ze+3wIl%^V3LBgGTEKJ#7bzU8k9*ra6guX}ST!`h?r%Li1%e=rr;Z3?dzN5f9KW5h{ zhbG0RP$eb8(bYS$**;(@S>#xu^#ZgdpmoJZrTOYp`5o+Iv}yauYr#9SueqYGQYOj! zs96L^yBBeKxg70 zgQ|*z3$j02ELtuNQ;WmYw>YuQtSEMwvaLOW%$U@T(YZf6BdwZpYH^z07!IoWHPsOB z|18M1&fU*79R`dn^N~7!Gqn<@P`SIrivFQS&WN?U(ujOh!$abAm=VWMJigwYmm~2#nVlv+nf+AR-@ToG zXH@NU{^gLppUK1V%`PVT)Za@)3yQ%yLv3=WGunrQ?{MqA>Z=rsbDM=S;amI|bpoAd zIIXRXe89cSi7uA1jUPM0;Feas61xyi%hwx#rPUikD%|_0Z;m~fwYxM)+wC50rBTp* zX1sm)b8;4tU{TJ?#Y&V=Ebd=>_Hu6m1M_}26_X)1Z4>@w*Ps6R{{JifU-*zZTKv5c zv?Ri88D1S|74;CXW;G4T%jd4EBO`H4M_$$NO#-UVaGOeYfu(xR zniiIm`n?N$=;O2G6AbmX4szn4toM@5d7POYog|z1*5|_dqwdqVqbG@PB_y{!pd8o` z9=2DV^s1gO@h}6M5+WiMrd;}i{l?(ETxEb@Rv zYHPDChPJw@bv{fu$V5W@EX`(MnI=|a3_wC&fQ3d{A`IFVf|z2^(ar{L&`wF3V2l*h z#)2W{!7Cs|po;8(X(%(?557pa#0llFNsD)d+Y@649wupqpN}$NzXw$-RPtdv#l)W2+X_)`cZ-9CyT&UuF|hfNmrN*s2PB}P2n&hL zOol(8`d(kJ+YI8dUzObMIex}Ak?U>3df2)sIh%Ne8s_Ka{Yz>8Pp_xM1+3$hqp}ql zpForsqSF=ofs@ntMLF9u`5iMhB|p3~CCcPvju@iW{y_$Ai+so`1v3t3_idaC-w?4{Y$L=OEt`mzH`Qz(?E>aPu=f5P*^> z_hD##*$LgP|7=kaU{92Adq(0JNsNaL-!uIQ1ND~VzAfZ4>9F|Vek+eY`|YEa4Y;_@ zDMfzfMR3a<$;@bQsP%R@+rLcfd>+sty!9bHn+!25OgX}YS_sT!WB8UMEh@oyEcD<# zpRn@QN4noS!;j{52!5;;V_^+*oCpGsFV09pYUw`LhIk1a0RDRa6RLoWwFqB&k{r^U zpjjag5CxD&R3&IKP7@{@v>ZMY(HUJ%p*93ys0I|~AH?;#5kW~IbOX>JGz0$a2KuoI zuXEhf*Vt>WnRE}0Q}nuu3p&`Ac77iz!cD3|clA#gWKU;dG;E|q3zawQM<~A*85_Gl z##;=tWJ-q>0bhW?zQRjY5Y2%!!3G!eTHn3QS6u5-uxN03DCl7j?Wn+Z-k zXTjINY11G*o3&fiuM-YSKdTwEU^stZpl;C<0_@04nBk&!Ps!=ttrdgv0bpl#N;%JU zi;L+*s1g-#^h()>Ody7{fFoi!reT`T;yw}4wB3}gJEV9;akozY5ILLy7x$b%1pq*B zu}jp_^9eR=N8rv%{i9~<_u6@Vm(1yBWk*7sMM&Y@XD&|%} zDCgcn$VyUlc!?fI=ETfW zw3iIbOSCHNcBPIaww;g`xW=D%z2O$JJP5A6Zo{E8x?#QUrJbR8_vcr7>-wk;>H}e} z3?A^+5#JsV{#X6y==?#Ec3>a8NeqHQsw^ zZ~qvy-{>dUCOz&iTta4+O&t)~aJ%m3e+@*&noXa_*N$zv$$~es{Jt}a%QJThRX|C) z=IvL38$={X8mWvPUwYVn+=8ys!A^)-47>=!$FrZw>cLTeX8|#jOk%Lm%#uH^Nxj>~ z>0~9qCMBKFjW^*i^t!6!jkR{js~f%kFThk_V$jnaejmEKtDm3U`-M!ZECcdbQsQ@h zvsw65h6AA*Y}N~}g4cLCUcC#<^0-^S(i$1kFG~HJ7p*|FMasA=@p@U?WmEr6yV*&S zcAP3$ER0z=A5=vqN-7mtrT(h3UZ?BGFEhqoy$Hry{p+;FH5MFw;_gXgXktB+r~6lE zO4Q}Ue$?A|uNaXP+AuNXB`0mcF4=ohf4U5ZpjB~BSd@cYB;9#gV0}Ip#Y#n^V2)RO zgC!-J?Oa09L(Dq$O<0SwH4I@?9UmsdHzsjMh4B{aY|eH4@VTM8Z`-in^pM}Q9&leV z(e}$khUrvrF>QBUn%IJzt?|{<5UY!I`Jtu(3BysFr)(~XP`^x06a@9I{5H(}{?2Y}Ja%@JZDogg4n8B|#Y-1LQ=kq7k@B6f;F8S#|MKt)dJ*lLYIv0qT= zC5PS7)V~sL3tqO{$J9vgUvd8FUHTOsGuq0xzxEBs#C~Cwa~T_YiW1H3-BjfBcHiUJ zQ97Z|kv|eoW`{(Kss$f(?d76RhS<>C!EL-s$n~P#*5G#UpV)Adhvx^Qq2M*A#~Css zV**f){EcmAge}dQYpe7file3ESx*L!P`34M+&ahWkbDfqF6PN70zO6Lyyjgdp~9)c zF-HA+)U!qL(*mROS}Xjzk7p=&OvHiJo*mNZ94PVnyXJfQv)Ot|!!Wb|hpep@8V zZy-bK1fVlI?>V1*tK_^K_@@2cfuWuHENpstKXY$-54{3-qt>8|LnvudH>y6T(vU1q z7e7*Uc z4&f8>XzDF6q}Y6uG$BKJHhO8m{1$k|L8+2eGWE}+bxxbckN8*un#Nr4udc(>$khcV52v)g%iKP@)+x0tXBy+_@hM(Z?@F|f$? zBQc6GaMD%WnV4t;*~+LA_R~4>tm-XsU~KHzemKe1@p^y7bjR9>V~?bgrzapULlj%=*JD5L8Fq1-ZK|Ebv6r&Tz5iXu z)~8AR@0Rd~nAX}Ml%kNcVy=<^@mvW-pNgD5#nt>v{g(B8NA!*S!Z~r<$;#gHctx;R z*pX?-?mqP;uG4d65EonRc>`_vJHf%m9K2vVmV<|PbM!=A#e^CXxJw!qb`Hx?3S_uw z3&!)zm5J+8xLiIp%#my5B(Xc!UhGbsl0Ih`%8`xU3qQFu6}@?B%lV-WoyYiAIo=H6%%|bQK-|V(`COSGCTG2b0GcZliG30Xw47}9BK<1#X#eYf$s*?? z+nP6roQ#r&jT3Lma&~m!Bg*Fm4^I_r&sN$B3ba6a3JzRvd5P8Mcm&!6}_C+pQZraKcVtk2MAI&X`wf z_-$&9H~dO09=aHnt*3dT%kI_KZ~u_`A#DsFy!&yhn&woKL4>o;tf&73^m+in>Nj}BPTuVbe? z6k%MW=I1Yi)zL*HMh54c6VO1cV^txEY7G01#H(dTFnLWk$YthoE2 zkC2sGTSB*C#gn-nT2I#xVHIYd-owj-_Otl##wccUsNU^%9FB-=cePC4cW0f5+NAS) zHd`GQG9g3@oOT`p7T;Skl0~-lA;mD3bFtR)+ZTja@L}+=+fPP|`x76AlVFZ^4l*ke zI@9){XUSmEb1_H*`*x=fn6gcxl4QFF5DBA1QI>jo9O6G1moAw(&_M=C=_ijfocnmF zl7@wzDWwFp3E3@6|4!&^S-4&oJvcubJK!zs?N&bjP0coQAx^OuPIhw|g+ni5X_Bko z2HRZ)hwKfC$>LmZkX0)?PhPyenMV)j!s+?!rr&%W3Zd_{qa~6*kQ)jK2YDvv_MCNv zzmafW=*S0lL+9L7M0`t?{+K&^ypsx^i7A|v1tcm6XQbA zndiZInX!56WwYINuNbn{Pbu(MFzXv(*c?2kMw=uMoj9xwsxr2o1W8|^Fk{*>k;TJjV z+>S>L^hMy4kg&NQ^vaXalG6Yf##IUno=@JB8XcB38;DQiG9K2+yT9l&V1=ep$0Rh9 zI5P3q^B^3>4h$K7X6zqRs8D14x(ViD(I)d};7GgX%Vk0Ke?X}e=7@WI|f=FUXYw`ymh zSA5a{=JFL&JEqllvcPA{YcAPdWt*#5!g*%E%Y+gRcakR|SCaJP{w$=HZXzlSG| zYlbR-7xv2fnvH2i;3K%@$>&%6OK0YK7e~7$$9nsOU*82-VekNjA0Z9P$xwtUU;AKpgibrkgI%NSsYanmu?DIwE* zb0Kqa1-ZDHmZt9t&La4geP;pW|S#e|4O>CqVq#ES;VYBs_lQ^#; zcM2XE8F%RYv7vz+S?3_#qJ+DGg7^i87gaCs*vWv@@C3A`l!o`FE5f#|7M=$8!EJ&) zf64+iBA}wEP-j(_T9H1X^i#9ZXu!IaM`3`pr#X+3zrsfw`Ck}6*8BApk0gbI|EjMr ze3|%csC_|8?jQTNqDg8OA!P2Wo!!Jk{b=Wykni{p?rod=9o-Lnj%Exmv zb!Ldzr}S%(7ZF3sJ z`#}nfSrmGxOu9 zzPXcQ{2KY|`Sa<5U!!rVB2u6H|0XmA?zwp#__@`T@O{kvWcBOk+49W8M-MK8nXFi( zo^zHcb#Y5Z&msTJ7Ytz_O|8do@4h*Cu3u62v)1m@(w!l_T(k}M)&02wgI$eXPfs&l zwNDK@^W_VZ6BVO_{^q+*lDl`#&b~INe{mar@x@eOapB~211a^Ibx!6*W#|jYiS)X~ zEyY>uxu!Xm51jtJ>~cOGOB{g33s}@3Pnq-9zn|f97uwFJFQ3^2#b0Qi5v^|_o6|P_ zm=+0&42%;I=uf_EyU@+OT9x=kDZ@eVn^0{B(Tlf66!fy`)M)X&Ro871++N;_*ffq9 zS=E_tTVnMmqj-BSqbM80>)My{F!Z9t(QhpG;2f2W+3tm)N-L_a?7ljS`d^&T*!YM+ zqJuf*yG8c%ULuYme;|oUxJ}WGkF@%}5M;#fobs)!erM0Ci<^wyZ_Z(6>!Am?SpwG% znl`W{Tkq@if2OXZ%33d_+ymNYZ9|>sYkEV5x@45+y?armj>)omy_^?oT*I$^WvBKk zX}KXrS*jCX!i&CY`;x?M_g)Qb%+NdU?h!GW&KejcK@2e zu7k8AK2%e-I_873GM5$K41UEcmDX@=cy|k9i(#)!->Xy=S}O?*-yl<*5-?LQ^~xQO z`*3`;H{>J7C`vr!(T*gB@R-T(EiM#wn>-5KN?h?O~`9yRDC z#p|9^QNE&STjmUv{nA?|*TKm322KmX5SUF{XFO0^g5W;BiFkyupT~O=@~D120dfRo z+j77nxn zVyx@2zY=E<2A*>Dal?0;wR4$R{w>JlFno)?xkp7Xz&nhbTd{Z68 z@7-N%bSTa*)fZii^`xO{4~&A#gESB$_sPyRzPaij>(|#-6-Ehd=G5@IjaLH~UaOML zjB4&pzkTBBn`+%m9GR#d?Fz?+rEQH$8p$&!_pA^fo0`;%@`*pQ^KIWASlmiI@8L&b znFpuWeHeGM3{MY&LV~x}A0llYmQRjd9-1hBY15Io%~Gsx}yw;TiwD?yxQlv#FV# zwuOq7QseC8(bqP+8dM9mqM;3hgGH@`as#owNUtp6aY;2;W zH9g$!NL_O_BVcDbhrMZ{r1tXz-UO_>gKHzYHN3vp12TqGyS6?dZfawcZ_}gwA|rnF z)0@NSp|K(v>y3x=G(>81;l{>PTC;U+MJImrxKdQ%Da?X$vE}GKBtC?KsmO<+^r6Y5V=G4hYt95Karm$xA)UUDWHWntexHN7yDI+ujFemZUi7kZQS3Ky#n0+h?R=~J+-q;HUwOQ=_saXn z=-hFcyhzda7ka~xV~1{~qZ}G^8~w6kjR8(+uHO3w;%B+vHCU=R*Fd7yZ627rd0 z%u7b1bp*_b0AJ|Jea7li<>pCmO51$913c#Wq;)xN6Qd zy$@DIW)3Wr7W4B(gG$Tq-@h~2JK{+0 z`QC!L+_#t>8XgpU5WMVn^Nm4svsf2M5g>)7)yRqw*XBCd{fdRuqTqSg!dOLMC4go{IGf>}}g5vtECCe#t@Y955s zl7Vyp1fiR_!>+vebI6)y4gA=!kBVB*zT0ApjhatK?!oY)cge)l`XS|IkKOm@#I*fi z-+31>QdMe~orpNw2EQ#(@cxRd!tH=d_a02`owIInt`)j!Jdk$|sphkqaK*aH7RC!M zsh#Tj9GLX^!LFL~YQI|0g2=V2_T{^7)ndUoi|(>UYl}KNviaob*!_xYlNKId@}SiF zsE06bHDb+qOS8qrz#rJQ3c9F3ZIElZlxKp+IL?mo>reVBBPR4vTf237^Ot|E&ijJN zg2!w5v#<(8^YqLrpVeP#9}f-F&9`M(|&Md6K;K1vM5}?$mXV;6$rQIbeFy^0w z>j-elaV8cKtsuHu@zE|K3Ft7;TmiHT$&hc^J7tGiygwbb!jq8xHZNPib!~ZmF>qts zPb_49$!E(hw-m=Lk;jw%nW>nwUqxSa_=dIK=VJZylZ;)b2#6|lTTgs_(c2Sj)ws$JgZ%QHxp{UXyJf+WjvxqT!sMIZ~NEu z^JKZ=3At~8_vzucMeBGoD*4KUQL83WjyED+;U{iXNyn)JliWai985x!X{=YeY%UyA zAuEHGEY&9*n-c+imGVX&a>ViIDqUjmYQHTgpICm4=>)7Ei^zp5WhK&tAkOXd5&qy_ zE6~yWO{pEl6Wvzthco=#;(Xh+*SC{GRD$Qup~_}iNByi2h?N;mPaYtKJcC*Odh!OT z>)?j?Q5RoO@yct5Wq80>dC$8J-5mvZOIwNUACBkIlVN9ky#`~IiNhb*i|u^~&Ui-+kYg)Ug} z8slpTlOx2>(~PLnhc<}P6k_v3(L}c&Gqu*C)8DnJu{IB@eDZvB4h-#5>kP_AB}=wu z@}9Fa?I6u=DIO{6#a@elCBT>}Vo!hlRgMeOGZ`0JD?q|axx33BJo>BT>CV1dNIQU+ zJ|9L^B|SjU=h3Jzh2!rRL)R$3V0W8?g4f3;(YTH@@Kt$;bqLGbL*(%OyFvc88vumJ?t7Qj!BJf*8A&Ve`d&N!%|Sr{WvPGL9&^jg*H>)G0)J7Fz8`A-rvaYG4M zLrj<{en#-YQH?C|^h`dk;HS0Xnv9rkzSZD|*04V>ripg71_6swG|2tpig2r?NsaZc zS(sew_TN&EGP7%*k9v@t((B!*X|iH4*QDl8kij4LQ0uN2@7Msv&)T8RUO|_dY$1PV zbR_Q{IdI?n2TkpD>W7jA(B`;i5w7%}O7W}K~ zl%qYnyKo*qwP#?5o*3N(QAC@5FMMgDmE5f@lC}fmbx&yCpLU5B)vJQvrC=EEP4FMLELPhm3rv=&;u$ zFfQXs=XskNgn>sY+?Y^@nXD+i7c&@@-3zUjjQv-FhZ25}&MS3OLj?rLLQCfMQIzoB zjTQ>%Fg$$V57+1dllR9vO(5ls1$_GY3;^Pychd1#V9ny4nOp#`AK!ENw`Gf9*=SEzH zY^neIBofyrFuTeXg1kCZGmrAB>52I%SJyhq?>qKNYZ0v17dgeNF*V1y(Z}mhWfbl; z7(=VVb`A+SaQO5I+C<7P$6=0IHNu6sq!O0So?~3SH12?D?O%iK3#2Wrd*`OI#Lw2KkF>p$7hd44+mLd5`jQ$EM>#hIJ!_!l+xODKfY36t#$YlK2 zH50c<*z5ovO@r^vtbQ#ol11^wn{0ISuYXGX$vE7Ty7ItsQ}~SIL$Z+b zUh@3Glq-w9V1tUjKI5CL5jGOS*jp}cT1tdm_9oS;>kwII#DDAjs7J#4 zwO8pEo1FR{PBW`ngOxTF<9nYL-&eI+C@^Rmr>0dLULD7-7O$X-h4;z+;mwachYCub z*_6_PEIsaSiU{h~V6hwP-w~eX)yj_+3*coA@K(fh^Tx=?(CT;){t%=`{uObt?@rHb2H_JUHWA^BPNuTJu2i@IACAKt=aGVby1kI_!5$|30j78 zT%GR$TcYQr(PhWj8|yAahYCA{B=ZZ>g-@~A!?9y zzipFP8aOx?)kNC;(zN&a`liOLo?Qr23(evz(3)3&Gwl7b0n*JnR{5v=*`Dy!Ru|G_ z$h{Cf$O>U=y%ikqX3QKw0*4ZVx)xPSAJn^;ry(KC##ZeWTj8Flra1|=g>2=ZLlIWK zx!+|I0a*O$nDGTFg}({hbG|M``zAi166yLB+|DJ!NqC!hJR(vMz~xQ^Bm$&fqBx&9 z;(qh)iuUQhcN))X3GUYzYD$)L_Rv>Hk6XGQgK{daKi8q!Qf-6|RNI$Y<+HhNzR>5gPjm5D08D?)2nizL9wl<&aj7-?(lYp!yq9wFEuY-hv?@>yGdz z5_r$uS}(0_u6{J1;?KHG9*Zf_IHIF_JYE%jXBheh!%2Tq+-h(JgDH1hG0nsr@rO|F zEM3-%xWHiZ+@PRm9zCB~V|YG#)AIXKcUCJ>m7Z+kPPD_8xbOP}-Vz_J-QCdM9f8^n z(2BhV&9zB2Z?A;!`N4z|+*~O@Z^pczHUnOLR9x|N*amJu_o*#x{vOSS?``*{VdN&% zx1Y?%_Nul^D~D_}B|AJkvP-YX6Gj(5oxU-xm1D*G_Q@@EqoIbkCl7Xhe@}tAmpn24 zly!R%;pu;)I0GYJ(z_u3Y^B8jM%mq}!H32*l~{W8j&PC>7!{*a*0~u6%}Fq|>)`z( z)AD|w@wCiKMWj!&hW){%#U-~6>+TImb_CS!kK@OD!!0f&7u=FIKiHRjAAfFxaHC}A z!MAWjz5MWTOreV#^Z6q&HENJis;aGf{k@^rttJg#z#H}Ny_ z`6XjQaSw~`*}6Mk_^?g+?y!uEd%wW7E8pUVlTCM0)We?_B&3#`4!0HWAfL!?Wh3@B zrVnehP&EaxCll}Y`$n(@B2Nk!fUE=94+H#w^6W@?&2 zGcneOLF9q%3H_uN01761%^wec24++1=Nh<+i&ql4)f4%=swG^ zEBVnoHSe#-5`t0`y;C;r12UVMw2zv1&r_3_{F8Rxtq%LJWcEw2|Ku}k_4uj(f-7AS zUWo4J*j``NjB$-JR~(MGU^MZ;?qH_C7k1+XhdCT(nc9 z-{5VdpXY7cV-vGoORd->J`zgUYKt{b#Nfeq+M#WZ+|n!Qm=+bRoXZGxT*l()4dTcR zYwp#UZ&U^E)OrERgZDF@g8u&OOPA&|soxRraI~N8@xsDr^yrMfjqo!Hb$yQ`!E;=M zxz5vozgxb*q@`Rg3#~rVvJ5{vZmjL}!&t}Er;h*43;#{o-4PDI)2IeKK-kuuyCn;z z{LMwL!})fKW`G0dhe#QKa65RZX625SVoXr`SzRU5ntJ@TC(-^~HvvkMD)F}tGnspZXs;tD++H@!@6yky zmlv5Tmp1g{dG!{ciaa)blXHK$=&9gzobRLo+<&u~n!X<0mtP3LhV6+lPIy#wjm%7E zY?$%q33u%S(|${bst((2LD6HK@=Rr2GQfpU?N{aEdCyk18r7BdNWVKTLsuOEH9|m1 z{0eho=bzBINB$~!344X9LFz!s2ytUABKnKEQngam@tdyK=#C&qew!&MJ&aVj5vV6Apq#%geccBhC@3b25+&;$i=OQ3}nQpaKSH&%pet6+>0g$}uGaP8?unZ-U zmv0><5ND^4VjvS+4+naeyHA0wiDKd-GXtv*d#t@pF|uc?NwosA1{gt#6MH(+qc+#T zq5Y&CV5d8G!VZc|*X~u`^Uc({Q7sjALp)q;&&xcv?w8JOu3sYMKd+^iSa0)69(FNSvY;yzm%yX{~Ek_hRcFf@tFE)=Y1|8gj5+OS`mma0$-$7DO~J%89* zeFN)rcOY47W0XM>AWoVUNIue6rOW`;u4R@_4v(#lW6+Q6%=g`=Yn-llO_k2J(p?LC z^6^ZAuuYd+tY!JbIvR8(IA>pcxwb~5s2XS7Y&F~TNi2B9AP~+dqLE4lal41+$^VoI zx+Gn3NGkiZbL-$5<#3og><;El2F4!CAPX|c8u-yxiqCLOY%{FS)2GOs(lL>eUU|=? zb?-f93%UF9o*L{Ro|)&mx4;zZN_dpRjxf$0P3QbPiA<_uDzH5Z!SKt=UwZBE2S=5ga;4!=rl?o8cbW5#Yu>LJ=a@l` z_9Q3;5W01-PrtpPO%Xh?ro-hQd2-0YAVZbR(|xYm#qovC5`YhIQt$83e+qeBfY%zt z46FQcBad`YQ$Xt17DC8_o;GDggyjCY!1(V(G0pQP;n5FkzCf}PYgf=Ky@Wj{W5Q#e zA=@hOz0dv;YKkDu96VWo=)}FMKSMN4bU4xe_|3@^T}S+ZX{S}JZo(peEPG-KE5$by zHvV>V)m;EnfKQ!1>Y%N>E^9n}0q%>^LHa*P&`gn({_v-t{{C%Y8f{s?g@BY8o9cD% z5LDs|a=!~h{zzDWQ3B zR0h*NhMAn2L`5YF=P2wbwXVoeG?QX!&uZxv6aLB-*+#ORS)luBi2Q+PlltgMeqXCDz2l zot0KW844ZH9XM`3KR>_CuYdGir&ssoyHFLM^iuDB@}K~=c4KE(zScLj0Fr1^1iNN* zB~9gFz();tlS4kWvGNB--nACqUZ%kfw&`+DJnw}yX0W%LADH)qQAxH%Ywzxk{Mm3F zZ7no7Tz_q@jK+=W9zYo$TVgMs7!R6!_)t30)p#Ky(;|WO!Qd(*DPuG<9D&}b8Rl}W9@+<+b^~k(` zb2zuzbI<@4ezadoWxKxTROU&2ZqxO_gyKuf1z&*K!%Q_mwKR<=sht*I^u^k_LUBtHv8*f z5cq#k03)LamIi%;GM~TG>4VNUjO)$Ja#H{zz^O>xNG+~V05m#?gnCRq?OqD<2dGC1 zvL}12*gwEXX(HgSWSLOno8=5Ahc|^V^~x7z30?2%s_u96R(kJCX`JH@={!rfh%f<2cs7gysV~1+H(g$w)!8-)BhF$ec~Ms2U6^r zl+2M45epO7IQS<-M+VJ+r9aD3T3?B!LH{{K0`=C`i!Afb<#jh{Q&q=gYusN56@rJW zR?wEv8S4iDAGGiH)fs3DEvVdgf+SUZ0D21Kz_9RsEO~h>kzsM z`Ld_E(V@YM-9pc8Et$2vYTHO$o1Q*SG*4kF4d*@IvlrKWc(A_)JNs{u8+aGps0}n1 zQ`+T2EiA@{Yah~#m#LgZ8fG$B8GH#}{nMgr*4bmNba@o>XVZs2gj1vOuv&viZ+!*a<{Vx?2=gEJr2UpP>UR2~$s zzb;RKxi+C0q+w!nsgWeF;GGPm2jluX-myUd_jr?Lb0FDYV;r?_WajaeanKQmw={d48Z_!_+Tb3yY$R2Y5+hG0wA>Mu zMLwGx&`j|2yK^VK@O7OS`&%o$HMe`w4b~XKcs^sgykxrNflA?%wNESP?9Fbq-n37p zTE#ml>6*7Lx(lfJI@e_kWlpup4o6R@m^VE6m~mtt9X6FmwnU%N zt*ZlNN+&)3bX4rce!JvNpjY1cDCl|AP$j13@%+K?ncBd~3+p5|+TlMKw@P&;3d`vG ze;a^(R&a$cYGrx67_SZi?&!Bx&^dhJ3$tbar4@aTQ=IWnxZi|VIAx?uaXx-}d~*Uy zan4S^uETZqH!o2%gi9458EF`)-CK0Q+naawTrbZJC12c_Mx6xo3FMK@4*{gJyGta5 z%MTzx`A$mq&N@N9&E)_W7wu?vm|1O^zOQpRZ1S!dr`B9>=RcjrBbNb@z zAw4PS3mv+QwOFHw9GI?Y_f%twN&Ib5&u*Qa7k`|%AH}AkGgv0-3+<8IITqm_XB14uDWYPyRN&}kT8BH zYUk}JKZL^D9RGbPSp_L@m(+t(S{%aacvp3VkhGldz{jF>+z*_^FB_&H@~WcodbgHc z0=Uk8wxIVArX1+Nz26y53CVKEp-h3u2-so#u!*^+S$deZW~Ie4_y?cUN0T{%VNFgS z(W8U;YHGnHwOaGiaFd57BO^tJjWT;f zzUYe9Lr?0|7Wx`vG~gQB@cNF(a?1^(K6Cfga4=yc(Q3vIwVr#(G0=0Lwv2@*Gh&os zlm*|~!&g4wC$zd3)Yw8ufEm5op3Xk$MZuT_BWiCXVOIyI?ZUkF?P2?U)nQBdA4jHz zsB`h)Owu~f#zzyXO6L zlwS$6n>3$sg}sj-S-(lXyACKOncL(L;Y8gXKA(*tPt*LfwRs4}MnnuO{JJf77Nisjja3 z#XZ4?!CLCigPK~+E2izfd~f-W9Kjy7D>##dzwJd=fMHpHWd=iWs{sk$ijt59O9oG! z+!F1p?s0DbVJkB7FOfYu^x+9l@xF3soQqk~TXuJ($|xy<|tBndHfm2h)7G7@_OjhdjZ=Z zB9GfmC~^3g^jW=^+N4DYY6rC4(U5jb#n7OovJ06{=n+B=2*11uUpBCbepGX=|3J~f z`FNl6)rIFq%eTY3IYK^V(vRnTm0zOsW;tIyd@aZ1NO#kRki^?NG;jo!_86ny)9xFw zcFtdH%lMQWjyAbhul`KZJQtCNC36deF83t`c1Z<&M@Cyc%~uF|d6GN<3c6@ebM8aD ziB{dt4;r^RhW!{qLOO-R_vU}keS3R>Asn%065gHt6N@=Q@`|hX9Xf}nsZt5hL$7*p zzwQr;0D)76;s_V!Ens+JGcS;G_Ia0gezm}wn@1$dhr5I`3K`8rl+1d_NF5$R+`4%< z*)$?mZXR&=MGEnXxw!nk!rbhr#1M1r4or-wCy0;_Y*e59d)q7!I@OcGuFqJTyF{B8;$JN zCe6S+y8%9l2kOn*)>GZSPbpi+Z*Cc|U&Te_wHg=s!EN?`9$0iijOJp*Kl9P5+)Y2% zdYaduY(Ho#fT7+<*fKLIY(5Ds88Lr^OZkjAOZFL6kq?^wx!Fx(JHO;}mfzUG$8n_r z^(7k`4ToE%E6twx;qsoDm)2jQwS^r&i#LQlwx-q~X0wyaV>OL;y}hZ#C7P)n^+~W< zeFM`c;j7E$j2~s|Wl?MH1bp)+@w{`V?q1~QpXKRsCYXRk^Zy@${kO2rwzmX>DfD`E zMKFLpw9a?FgY`jo=;Lko4t*S@p7M!2mZ3z31}Q5DEsJhn;3WZ`64qeR&j8#+GXwGE zew|Okp~nWKeaW)9*e~$7a}2J+<-#Ku=sqLGh=YKY|OG-<6^URsL z%Cv8PJYv(ytUn4(M9}5!VJWpPDF#m&KO!OrUw#t3i0?`hnVeb$-BjkFtoBQ6vp{fq zRHpbgFGLo3ue(mE%E)$`8zbxLgIc^Ro~lu|`lBh?yZbTvy{INqA`YgznAsKir*iZC zyg)!5>ajabh;e#H^+XJoegk&+QI0tf1M5#>B%nxD9|^m_m{ z!-Jccqu{{jHTAhh^XrJ3=6nQXxjVW zZ1KR(NUSHT?WMJN>dcvCDoEMcB@?P{C@9w}HjTMTi?y3<?Aweduv z*wNuBoAcDy&%gS-d&*gDn@(Pm`UQA=e$=L>US(llPrso%4xwZter1Hed?aJ}3E3l% z;#O{n49NfbR{55AFJo~S*3w_$Qb;3vJX>sFW~Vbzall=|o^I{IT-0nLpSz_GmTQ8RF?`@8Umvr(p0!~#@&n|L zj#D2Iqr(>YsPHPY0x4mY1*!5t&xw=AwoLUIVYQ8c9)1B+8)NlK#H`KMUtm{X6O(G2 z>N^@N>(OTQv^J!7$^~;Ygwym97gI5dxhzr2_T~PU0fz9h6{$C}k)f<9#s0Z84$Zk2 z9JcagN4EylGRXIo%dt904<;>O8Ii^7 zu4{E2a}z2p^d@nK=kfz%$a0q;T_0-PWeR?-EZzA^E8-k4{rnTarG<9eSI2{P;{H_g z^`+_pH@9D?s(WLUUi2Nz`3v?l_@_UjJ;Vwzg*^s9) zPEs5K`6Tew^?DDIK@?+0F zSX6(_l1CtL$VxauLT=Agi!%MZ;9Xk%jLACp3@hNZ|)|44eo)igsk zC(Rwq^JO63tZ(BQ_3Fi~r4Q`V4|S$KDZAvwhNfyvFD($3z6@Q5R0l4B1Y}mN%G9M} zH=+TaA2!$BM`m^o*nR{7y2OFAVAt!$~*qjz*j z=z)t}J#*l*ajLa7H6$Qk`$v;Gma9QB)*)*FqO7(^-Sx)|Mw~2 zrW};A#zt9zdW=#0xLCw-cn!yy*3Y|le~FfTaS+S9?wS#xx01nhso+9QgK2FGJv!P} z|5Y(&Pc83kZSD&!i`H-{N^^w)R{`Q9;+Hv}zDX2hlu5lUlmvVwC8LO<-*OXcIJj|p z`gu`8o!pVvXY^u{xDX8~cDs6KvQC{(IN-cQJU3KV*DeZ3`=Y(8cY)~lfG_!Y4X3@6 zz#ErPT)Rf^S`R_*x-PCA`6&{<+kV0L<=_WZy+r0qRbA(}s!9{lMKhChjvLEdZqpWdPp?kD=4A{tD^`+t@={3;og_IEEb?hu{WK3NPZ|$;KH)Ln0P0) zab5usM*}Js7fN7ABj+}HCER;#4HpI4R1ngVx>d^~D#3bEx@?|P*;v5;7Qp0SK)Crm zKXkbhh7iO51iHj`K><4n$%7DhxV3A=H|ZN!xjZ!li-o+mjP{kYi(eWWyVsMuuflTaoEk~=G13v zbKIjNrw7$6?Q=44K)Y~ipob6N+TRofOUr%F@gMSywt;~zkUwF%)AoYIEN+E{spECs z-bIj&#aPsxerD6%`O^cN*Nm4N;Rhgrfi9`HH(T5WZ%WP59yWE&3XJAT8WAVOOowL- zVD^@!F)^oV)zyot&i#gX1HW-_HbXm@e?1Ck?}rT;p(f6Ed%Y^k#(l;95Fz7y>nSK< znUq&l3I?Dadzpko&U?|@%`J#2iRBY1^Sv-N!+U2aVwGop@ob^rwr6j z+Nwf?0Rn=mNz`3#;M(eg(pHhr*g{d*fTN;<(AYVy(5iN4?%oCb7wcK%?Z&i^Z+dEbM zj7I1F$kXlsfi3mLQ&SvS_rc$?;bg#r_KN@sOX7VK=uM~|pW;h7YNV|30rO3NFV{s0IMh0z?0UbRZ7$0SH)FpI3Uh}WN{tBVr zf)Gt(F+%#zPLy-Mgphdrl$e!QWrAb`sA>M=&ji11$%!>hq7t}w)g*rVRXE4D;}XZ{ z=SWVmHGi<)2WLPeMJdbf&mjv6E`1!$BThevimtd5P&L1D)^QxT|iA&8KzuwekFNrv|B2o7SkiPgdG9W9Oi*ntdH^-nU$;mpwL zOM6gCU-h$zeBpiOzf?W`las74&w}a(2&HU-F$r*YoPo*C-}+e1{-d=k=3bba0R=w?WcXOgl+rJmx)i-1*G{49 z)nZ_M+~!^smk2-(JhjRr$n$wf-aq?upT1of^A1)m1NPdc<<5(lzmOXpzQ5w`7j6@W zDV)LC`5e`SjgFfabxREpA}5ns>OlEtIAwGb6On}rcd?h&|gv<%x}uVSfz?&O(0>#OS7 z`2Eg=s#u}WvLP28n)X#CQdo{FH0a=0r1%`4G)JB^*3hg!iN+4RRO;n%oCQkp)V-|> zn~MdVmggIbQ66dsbE)L<4*6Y71PJQ^J--Ml2{AZSA}{nt!qS>JuW+OTu121nJ3GMb zgw=6O)RB%2+RMEbdGhHCn4VDND?g6Fz2m^a7`cUG;-N>1gl@seZb6&&%SVm#G2%ME zxsLhg@HoDxAT*HcCL<)Jx# zX#{N9-~XvY&bSdTc&PCk79EN~uN^l^Q#8=`#hWf}wbld z_YJpf3LyP8jh*xdqE97ayg-a!IvPWG01Ll4F*kB-Qeci7kt|6 z*?YQ2z3W-F`Ubp%1gCnByt|9sVj3RFKFw=DqYTwA7}WD7zY9M5fi>yRRxWGAp7ZIm zQ4Jyy{7>MW7-fVlmy9F(uwlEmTBg{Yx8488n`Notl;J?ma@ zVpG0DYL%Ee>4|WrO^ZQ%!|0FQk%XWCDR@|ePa}CnOx^iqcVn%D?k?ZT4@ohl-_V@R;ot%t0vdT384;y}L>!4<8`aJi+FBOWxgPzBLn}1T9 z&Fd3du3tc?bl*1;35xBW3M-A74yul6I><)Gc$6K+&MI1}2X)@p$e;`++?HVfEf-Hr z!HRBie8{aMf>BISHzZOl0P|eml-{NBGHj?1@toYx@7<;j- zTye~izQ*QhBPk7o;Hlk!`jr_5J+{fJ@OE(GK)D9<+lnuJ5VKLu^3Q|2e}|soN*4Z) zL!Yx%;{aR1!nOrWvuNunEXu)VEu2(OKFt0%{?~kv!e93zawK;eB>dXlNH-Z4`X(Vc25 zj_2RFZo2(Q8A#ODJ9+;Vy9CAB&&+`UkKgc~K(?O_VVi=3Lr#FKII|{@RW-*O6qge; zW>yb5(Ci5b>6F?=sDBr%cZK*5=rm_-q|1ntu+_2l4mk0tay*mJEl+*_iM6+MY<6#L z7+h1xyLcKJaZL5CM#!!BNJQsLwLFRNK2eN&wC~=9{-i&S(W;9Bu~pkq$_EdOQ~vl} z{8c6x*a>F6Qt`aedi};xewvcVN2OQXsO@*!UXJ}obtrvFa@F@F9p-DfxPA>|me7*yzzMFp)shqw1n&(%E9M=F;~I9Xih9#d4NNG9Rp}kgC_*AF+!( z_*%%ig=kGdWF8RsK|@h9w(U?H1RfEoyI(xRXbYG$AaA&H|F4HyiVY#7I9pLv5ak!V zV*i*)89i#&@<1zUUn5gRXVX^tgvQWPE8^Ow^+BZsRHrzP4CpA;cm< zeTz!gz0Q#4;~t%V!vMz>IZs6K%=y(m^O7pM9v;pAo=V0Vs`%nYE^tW;h3^7w-YgZX zXdb`ExeLe#1Oim`;-b#aozXiH0*s%3FR^tym#6aB()laB6O?>Yr^+`p!a1>%KXWyUKWK?SoJ|;O0Ep4q)i=*CaF$`H9P~Q$Dn` zkY^%gkqha}l}bY3>c$DB^joBt7sKBxM~W^Y;|P@q*$#P1E-bL7%eVV0$jcGy-+iMl z_z~CUxlN_s#{HdtW0=$~l_R-+K&Zsbx|{cQBo>Pt*yoB0)#+V_B=GD7$F&FCc%?_V zd=1M@VK&Sj?e5IXQRYw7E9xBl>0}y@KJ=owuw$BSW&b+80&CUVl`=h@9@xkt2kBn?n)(fumznkied5O164&J?8(I&jr`HuP`7mJ!y z>_5v*aduJcpLrWg%FE!;i4Ln$1jG3q|JG5CbQ<{8p22Zq=)Gu}ifEa1g5*$VOfr{w zq$NSxcP>W962RU5y`7))`MGxXPoo_?&^LD$#c>B9=jE^V=6Kl`J~9##dl446KEj1< z_jd*xeNw(9aOvK*3qZ?jdr#~%AKhi{l;%qa{rF!wl8X!A$k#!@Z#;K)bYZ&fQ3`ZK z#7=*^C_5Dw>UBnr%k)HhXOmNAs~Z4(;rgmWjI9tR^X3V-(RMoKt$h~!26-HAmd zWS(FZ^+23&v`)iqcLvAaG$dbkwLMti@_RBnms<`(&nb{skuri43hD)2AGE4IR^Ek$ z6PzRMx(mVW?{#aOSc4hrbVJeb546r9zgh#coq}Q(;qP^Z3|q ziYJbO9oc=Y(8kpcrD#4p*4MoK)&8{GJ_wn!f1FJ(-<_cft!|BHY`$a>uerC8dXplI zx(sS>${kti{V9m-lbiU6zG8$k&%omJ%l}0xGp&)K<8~Ay zHjcxuHOb-q^cb}${J$exYz{qp#uB*7XYt?MR6YCP50_MOaPRjDbS>@qyS+aO61ne8 zbj^Dp;kNiWTm>MM@kOUMGNfu-o~A100$jR`0Iu@Py;YynBd#}y9Xkj7H#l%{{j!YE zUM`&T;eFrFY>eeAey|i*fn?Tzqc~bcy~;6D?3>EKP0@f#f3~gX zKi8rHI>4ke@aP(|jJEPU=s68@X zZw>lH0pE!t_mB=%1tV3MZ<7+dX$zojtX8#aQLaMxTO~qnXFJ=LHn}#dN-NsNFpXmv#XZPL%2DnsdH&TcVGdBpwkgQ? z%BY1m)xoQLrt!9kZm+O+eWMQK`P|(KHJo>=utPX1!odcw4!^_M(ki}_ohTzUTl$o2 zyi?YcF16@cM;^R_c>u0bk4L~X?wIN4o9w%)40tYpAEJI*R2WY4v3g2^XDtq!{+E&5 zvaeF?A8}~jH)H=|o?U(oIYf1VgP;9Rk6;IG-FPG;Lv@tJxhck)n{@QNT^S#6_q5E5 z$e{M)(p;QR0b-F6dZ&ANcKt4b`vCWzs?F)yJRabL3PAzKyw~p9EZop?c@pQ}8>s*| zjcXTl2A(|!4&hh^Jh_~kp?vH<2M>ooz+CSyJ(1HVLXPcmjNC^^z3CK;>_V3A=>t?r zj^MdyO+nxZ&ZivD47q&0BG%WqZ8@ztrb8a@|AKDq-G7aK_3BlMx_3(dqWBgGH1igy zqom*{xXAH+o42y(yV7p_kL394N6E2YRGqJj`gQvr<;Ls&7L9Hc;EGd23z#_@L!Ey~ zxOEWXqftjL#x-4uU4#Wa8zRT%Hg>1-i!6*QaAYth^bGfc3u+aMa(3VF*ti*uuezD>t&2 z{Ao&_9nH_639;N<@8;Rhi?tPqQ?VhtAuG5<3znOVx7dchkE!P0)A(s@yx8=U2;l|K zmiYq@@cS_B)T38QS$4s9%ULpK%+FNtj5jfpd@F@lsmk=ej~~gy zlRzqcQIOpm{!MC~U7g-2`GKRYS8PT|^Z9JNs7eGh`f;QjO^DJ7Z$Il2Dd&9s>Z{@? z`33LOFLjWQu3pKpz*m!qPIb!p{s=3moN#G&`@Zh`d0x-I{5Q@ypYP}U&K+8( z1qUpHcv#V207id@{~$_KHUjG2$}vq$X+@D(L@CfS=hcUfqkSOLcm_cvVg0>g4SrzMeIcZCVg|3?o(CQ zF<1rNw7xQG*S$IodS)K&moK^u&G)h zT|@c77)sr5BBC0h5g zZCswcc(b$h9o70x?(hr$L2UKZ+iM1v;rIQ%!7bIeoi^x|WZ{+}{(tsvDUnNd@&{($ zo8?5p%+dzGDDKvl?>Ha8~PxueK($L4O){RG-;LP*Ye$|H*^^38-#NQKVQ68B56vME%zS zaCS@|4g5RplL?NuQ@y`QC{h+O%;1}r$kG-1WpZS>3+zw+n5wUZSuxFw8xL)FkOov3 z@HB?F!q@L1T=mQA=?hXA)%u&G8IR!n%b8GfP+7_$?evJjf$xt$2jdh5F)?uB| zO(j+Y-zwOT>GKHx#o#>r7c%{YdUr+Jeg5LP; zx7pFa?|xy9Y%+C?e-mQB>h;Gsf;Tqa!@3|l3l+<-a6_qe>b&4Ft2;%)%TgUfo`N?_ zvB^R#0WlJ;|bmbx?;wkB+8#)DYJkV|4ip+SPZeEt zjEziV4KnIgv@1cODhlVfCTaHWZ?!$jR={7t% zpP`%ozjS76)N|icz$r4qhFkM*d8h95`dYn#t(SOgn5EX-a73L!g1Uk}0K*51s#387 z46?{SFa(y-IEWL?WT`$zF+#OLMA2O4@0vJ!@n>!%H=XZAUnISTr322{@IrHXVf8=~ zWC@Uhgr*X9}DnW zO>iE$ySw|F2_VHmKswy>9E*4B9oTZ;ae<#K|>U;sdknZ8pxO@b}3xR+mXroYRwn zo5cxdmkIG)5*)K-pZEkcP>vEz$Gz`LtggvhJq%o}p2xTnTr5mgzJpdV1j1W&EtO0& z*3M{wtQQk6DlF6lC42CG5>G(z$B*{RB79+Yz^cIcgtKYIC7(zr6rXT+V$Sa)xL9|X z{-KyG>e(I(BbWGuhjk!sPmu3F57%FJfOF0SlYB5a*G_oK%#0R!T`KGMY^pc#J90V)G z!Xi2C&@hSO{Wo721gwPKV-?VR6Q?|2K2=nAS$xn8>$In?^HYgKe86ix)fA)zu#M~E zkf-*Z;B!C5doG z$7wkUxhnO`i(zI_HyLcLx?f3Kv2xCZkCV;jUKWQiE^+ZH?a}IHFgtvUH|TjUv8b-Z zJKp*fVa)2Dse*aw3-DG56A+s>TX5UffnbnJ=-VI;Ek_Av%A}xE$xpSgS9rPTxI4jk*VB?~I{-tDgVm@PmKY)XIiqXXI*k zn9kwEnke-7e}g?EV8+%@q3r--x>$Q;i1*Hq%T)dR3^R{w4Z?>wXU<|=5ED$0YYd~W zv!Wp|s2_~~hg2Xy=SrPsIl+j%#VsCF)bQ{Yj{q!_DjQ;fy#QQDby&k zVe(XT9WfALOO1~uw(9v<&CH+&XrV(I(pOXj_YwD71y&{A_r8v&?;hH?7&#Jf$hD)^ zi#v@-z;sftg&zKaX2DNs`QSKN5(oLWARuC0eZh z+0zJt4rQW|G2>Q=*KNV6>lnWlCXc-z1L$+p;;NfMIF+eyB!NSrn3nfk;)6pCJB%in z4!z^)MCIgRuB*FY!}1@%@U=v+aQPqtEQKU!bSYi7pWKN=t`h3k97IXEmD@N)}y zU!&fm-J1L#MbxgTzXf8c=s%yX_}YUrsL_L0$h`&g|9E^sVL$He-%XklL~vY5_VKq! z392K$^*stw?%&Pe#4BL;yTWh0W;$ zK!%z4gwLG8Y4I1apVzjnvva4R_nopT;rn-=16T}TLxdPuK-XK@6O#%BU07aAPekrL zXvOTT)AGVDl|+vd0Rc;Bpc4Xnfy5$4a{aDusg|N{%6N`MD{1-E?HkPfON^*n3$o?o zSI!T-0lg`{q_0A@Y6=H)U7q|9 z=XzMl-oUSDHspO)c1aM)nL{ z&X+H(WjN2Asy`PqN^z0;L}e%bMP)}qd`iqpRVWG5&kr|*ma42`{C`_jz}7W% zI&U{L2o!;z@6nrrCgn70SE}!-zV!Xji+}`paaHQYas)G?>9Fw-xj$&eKfw734yr+* z!JELF_Uf%QUR<>d*qV6Vub1~|pUno|h#V)LRr9_fw; z6JiL+whcBj`2l#+H~pm*YOs^N4YQXG{W2-%x&HkSn3|N^Nf6rJ`|cOPD)c=ZtPx>9 z6~gs)Bj|qnTg4m5ovT(Qnnc(+i&WKo=yYEvp4S}@I|vORyI{F1Ac0$I*h^D%@);U8= zQN<&6Pp#y~9Q`on3d6)=B7K+EA>$CtUaP@BLi3%fE_r|OqQYOm2uGBzI7WKQd+iL@ ztNIIw7uD1lPP*RM-p1Dz+dC|?(+z;{z@veIvtn(`UtE)yd2{uh?k6ufG{2IS&b>q; z7cp+XMh7wF9s}BG%(#CSFMb|M_P06egX3B1)1i~Oxls53f z)b?KtPlHCKM~UKT@zj12-K~pKX|J2|T3T*=ClD}3 zXaqnT%lrVQOcf6J14?KSfJ@d^9Yc*jtA&AvmsnYLwPCLjWygb@wq(ZlYc8|As_@I< zNTUHWo#%cM2blzHaE+Y_63rv`Zr|Qmj}3@YaUzvLaZ3+z$o8gIAr2yJaFTu&uk4q0 z#qA6K4i~)~}r_O`fqftI@T4r6p z9_%50D$I!_Sy%v_U_IFTHP(bE`F!QLIAt#sl`rI;8Kod4hURq>bXmtWWJb`ae$8Uw zlHxdsQy`?=p+5Ij|5ApS6@L}dL;>^hfa73PsEojzhM4BYKkWn~(2#)Js$5|ibo6!Q z0Zk&2aJ6DR-c78QOvgNh^|{h>hk2_;iN|AA!KStWIRS#UA1X`J@8}Jj9T*H5V6oFJ zD;X9&?ewtfY_6~Q__hB2{&d(7(eF8e z4lENA!TPuaNaB#cliHW*H)BwPv&>X~EVX7qx&~kt<{%BTb3tAfO9G+E52+~HaPu^j z6XZ(!fTje*1S<)!wFQADYWx}TaOq;2z3V*U)C*L{53~^G)O!$^HdFWH7NXaK-gmNOg{2%T)tQZC(S`@= z3J;>B^>-9@U;Y*(`;dSxTWGhHi@Qu>d)F!r)OS>fI6XGea1N*9=$;xoe+Okw5%B6t z-JBKM$C(0~hP-+G1Bh+$HK@Ohsk(aDxoGVWK}NcPf!y3LhVcV>rURdN2Kqz&_M50# z@(T*Kam%u@vJ`dC6;|WkelVKop9kt2xb1ub&yOr;r=R@y^Y)kD)(-J`ePt55RHWLS z2o84_%h%pt3 z3x5`d;p?&$aR7;L<3e0`0c4=#D@4EK5=x6ManrR?Lr$r2wD>@ zQZlc!?)~K2gYY%mv;kIlMUqbEPZ?}7M7lSs!x(t-gY^BIYTAeWQ)e=xd^Ouk#DM4d z3M-D6NhM$M&sz1sYvZ_I3NjW?2b}-1r-lgB7`dd}Do|0@%w#>sX$ARCEX}lQR(*;q zJz;Ds85-^zr4N7RpdPp*<3v`SY-qZ;laL3Ir}PkxIl5C63vH5TDak%HCm+G%P;(Ko z2lx-}_=oxE>FL>rhn8pf)vi{rInQ!leQ?L{>*=>_aUWCC+sO>6sD!UyCCeznZ77GZSH#p_vRX?z0*IPvvt-1!(OqklOP)g*9uD{n22A8vr)2y=fU z71%l~UL<3!43%x=*fasln_?OXa}(4?h})HAXpWWSw0+ED$e9ehshtfO;#WwS$f(*j;Ky z9791Wtf3p0h*fBvJc9tcTiTIa1OrbHeZF2NU-Cn~{jDdA^8;M=QnL*J!h{Ke72ME+ z%*9`P3&Cqq))NeY!|z*Sy=XrATha@wk*x+lcw!~mh>d`38o#9q5eoYa7;afLcBjbp zLl%hhnOC$_mN_wWI9ZU!$Fxu(Z%@Nj-^hB0HD+!^9%&d+o_$Av@t1yI>$?WbWhbH! zzNN`+eqt2I9mSYHhdj-?k>Z+2@`T)uojPxAm$00;2ETPyif>J){E=>;Bu?Ei$R`u! znn1v9fOgt*pB{bwt`&Do5v~8Dzt~lj_Wrz=|M6$eZO+}`Bj&)PjN{Dttv9BFk(A)$ zy>B{&Ti{9ZjsDL4``gH0**Q5ISsPW)B$*Fhe~j*oh((N@?wL!mVP6{kLh1OO>j3&o z{6oIIzE2t>X0MXWa_ZA>Db;%A)&xX*Iu$+gDAOyKsV$Q+E^MvoSYjw&n0!^xIsVjR zP&yk7iDWFm~(5Ceuys?8taXO>n#s>CA!JVe+@Sx0wf?#^E1;H^aj+KRFAY_H=s`? zR9A|@8W0!%MfiCts@~Kcw8WvH3zh}6_?+ilDG6T7+<*()W=#X$STzA2bB4gZ1h_jD zwPo1u2xK*!+wAM-B<1PXt+G}Vf>}Q=ckpr1r-sv4tYq>xNXa5kTbL3puHw;$nNd4Y zI0K}k1+P&Q^hS#un$MMCou(xdc?7ZSAO83kcH^A3qSt257BnUMC_Prc$CxeQwRA~s z%j(`z&@f!Qk5o-56+Cb|AP zkH+enoc?Zgmw)GcwH7&8YN0RnxC|MLdF89wNeUA$w%R?r4LdAW|9J2-Fq!gq@tV%y zzQgGUc9L8({-m66%pZky_;ex84-PVw^xvwJ=P~XDkewe%N{F@ z&JZDO|$c>bLzNqe|NU1N8r;`pm~ZWg8gS{4Y5GNcB1A?250=yxn`@ zBnFCBtJwNE=e}Q8rhXs};b55g4t8OCV(By)AX^%Qwh1UeosGqvDn_gBP@gGg5{5oF z`xNAKnz3#(LHE!C=8P<1(rI)ot?_*hctNxPI!apT0Bg<7&5e*Brj-Ji{fi;gRI6Nk zmd0(|yxFiVsy!e8t8ctWpP7yffPMqqwyae5qOJsE@IsVsj%?~P&2Zp?c#H(_s$WNw zC#`if8}18fT2Ezr9`$`MoY}HFlsWLckPrs>L9W3~5*IKh2e8(*&~a%vW<%#J65UD| z69k#h2r})2OUQ1dDojcpm&&$>DO%EVK|_1qSG51epLS5^Td>-cF>u(JymQF#RXdDp zd@x)VFFzPlVH^~IRvE-8?=noYf|O2@B#_z>B)a@ve$Uwlp8+>5R5^%OaoiQar20Ey zR5>hpGc!{9e9=ya=~wIu``wYQ=IJ-do zu+qxrXl^~sFGNUgqVD)u4*yk_j#Xwmt+JaY$?Um>xjHuo5PE}EHMTc;-W8;zgyxc% z(Gln%RgwR9@==7FLES+ig{s!z!M{2b{)C}HgL#V-)Xje8zxb6f$IN5II&d#MJ|4o$ zU@tI1-QA21fiPfS#6Lz>GHJkGLMDK1tOgztY?-u5WeXyd zCd!ud-5H(eo+Jf#KZG~6^wh6P^p(~oCUlJQPSCY2Xy`DlqB;A~#%tvUVil+<7<@^~ zc9?*dY6INL;8lkmeSowfM1t!Gc!jCFks>t(cMAsT=Fb3fiGAQB6rJal9o|?SHDS zfZDgl{Lf9Ynw=$cXsJ9Q+~2tP{fD^wmMux)a?`v5=cAcN>1Qqpbp@R5kS9wFzAFDN zcLTFj9EKvRVEGPu{aS=}1e}I5wxBP2aAiT@?oIP!xE}I+Iv}IHZSih(5UP+kr#g`$ zz?>FY?%pmz@K)NIHl<#5L-pX?s&QJVl`|)u%4h@?c>@x~%r{rQQ&xqXE%?YLcR$d3 z*4lp--Y0X(A@~(?>`PmWQ2G3BWB*c{y0oHGeCP$Ip&#w{c|O!=%V`-EmNxuJ1t%Sk zQH8^g4e0ZmqdfY9>DFGRX_<-i1-0kQi=pG&E-aO@MgD zb*04JJSU?sbQj07r?nKWsWa{A`!8m8EziG|+SYJLG<3-8FLo;lJ=wa*xVL9xd<5L* zQZ!aic1`)ZW|pO5GC=w&ug_`hRuThty!caegcjcMIuE>BXUnC3pZ9Dt_*Li#)Bpc1 z{F_A@$YCO}$5V8?G?v5A|NVbm&YdkxFSkg!4k6n?@P*TIlKQKTR|%Eu1iTw7N_B3c zD2P6d)_O}$ym-W0SxQZ3@u&S8MpYcudrf=vbeu(pvWTZxj^uXdw17Hx26bX;(~A5D7qu0;XSL<#Xz#Aeh4 zyXQvWv7v`R=f~fz1>ZOU-*5iPe3ftfWWzByPfwaTi}#oiOlV#C1t*_E&l9)V9z*gQ z7{Ky(?5)j*2C8fSh8Y%Z~t$aQ_Id8jvq*Q*KqteDNanC`{ zdHwC})T40<*={J$RVOQ5k6q-$279vq)_{mRnif#03H3?_Me3({c%lmM!2Pmyp%04nrH7%mN5#5!auM60XlQ_B~N zVuQ<)8>obdhkzuW4b5B(bES%sIz|0bP>UDKtdBk;v;^2>+QH?gZg8d1#lDnxYmGlf zUo}4?PM-)|a)dm`nq$x7IawGrLhh%XwuY54jByjEGT4a*6<`ywfpSbFYVUPi+zf#x z7E-qmhElG1<Q!N>Zd$?fh(-QIf1hQ!w35e)XzRg?SPY5yY_y9wy5C{KFfgFAzD1>lU0z)w zwhNK-xv~5c(yms>uK7r#c1+f0foRp>I`NOUkjU$;Dr5x@a1|FjLuW_mG`z`suI<;I zp0E2)5j3Sv=beexZ%jpC;qE;?MHp2w);w%`YuFxIXFzOmD!EjDX!+z8V-KFZzAKATk8;~>PC#eb7_2uQjurb zY=6|)<^OQpPdMK{(V@K28TW1omHp+FbGh`BWdeae2XvX{b_?#>lWqzv)+t=c%_e4Q z^fl-HsJ{u-Jk*+fr+&s{J&-b05*%M|6^0la&MthA@n+s6Jx?s5F!@UT+GJiHttysv zq5DyGVe9Yp`?>k~kNlksKyZ68zOfnwSd>fes7?opmsg|Cm^fLSz%%peZ#RdIebMqe z6t>Ch9G@osG5cee^C-(fZYpNvIaohXi*jbPcPjLh<(f{;YYdF~@4Uk?)L)kr%5cbd z->hctjmzTF-G-?FvqUcuEc$;7iB`d!6BKqbXw1$AESb^VLJK^?2ODscF{N*P9>I)@ zb$qZ<2Hd02h2b2PG`LXm5BC=g-B7=4crGkcEJHEXlajYa#zFT1(ct@dku(-rz}Xm- zo?Zf7g4Mt+B5W1-l}%tqpK%TI1Q42EUW0!qmG^=9eM6>ksY3ife9V>hWZ^ET=20D9 z6o2BLkx~c0R8%OjF;SKfp`4yl-&e^8GK__BP*AV4c`jw|TM`h3m0enYE#1H-IQ0Xp zZNZ&~?qegvbs~~r=NqsJ6xYv<1@DvFo3FZk*VNRE3G_m;M605uEN`Kvw2Tg)YNCxC zsfLTy+Z9ZH@H|vU4H7h|s6G{|89!FDR8txp8YHYD2Sa3|zEg_dSDjXx>Z~!RKd}u4 zB3fQo5qTh61~!LJ8+%fHh9eZwh+WtLUu~S=j?yl*>escExa1($)hlfpBmP#q?6YOd zNBEm-f~&BTd@=pic{WYgq3M{7#?Sk}E%(fCCy2QxW7YFJDQEmd6Kud(VI6th!cfw) zn|qo!RM15aqbEg*zJ!{}sOQ!jrpuTXL>GOlb1gHG8Hm4g_tg-+SY7(b!TuR*v60*) z_TA+seq45;bM2!djE0ws%fk&d?T()T=nGzY!k^dA`mewWhD!Q}_iU06&F=jEdh^Pa`-P4n0e)?6HO`B^N0MbGky?ySj- z)*-+94(IbN385valV@L5eU4WgSMS64WzDg-|HENuzU z1*l#AF&&3^aE@b!I~%YSXse=PPvDKE2?zDP6~F`F5}p_8+Yj*s<&r$W>Edu@>?r|j zS0?QD>0-Yg4tW~abjFHBg3=6`z9bI%ilG~VFJ_)7As9of_n_@($7Uec@`doAztE4; z$?tugcg{}Wt)!9K;3bZL-cU(4pO+?i>Q7UpcN`rpLvVYyE@LCw8HM3x=PqJzDVdy- zhhC=YNl+4JDsENUx?It6+VxglIBnJ{_9-A|sUC&3BMNAt1VrpeC7zx_s%zEdbc8BMg$T#O+ zm{_Xk6X{#nPW|GFD?P3#G=5A!h&{l1i0=`&$O?Eq%jC!Uq>-a$|K@t@T_)=p#zP1> z-)S5ZtGt_svcQmg;D4PjieO*CvCn+f#@N_T<-XcbpLiJynU`vJ!V^F1o4yWMe;eUj zMY*K%U@$kVEw@~-KW)~b(qSVw-tgJD=24f{EfGPN5Cmx~KeEBC+2~tcy$bX4!HFaq zI<8b=3xPNgFi&S8BC!VX_W0X^Bgq`_Wt&tTlXa5;R zp4*iSJ;SiBjpo{?*ptv6fICWps?RMZ8T8_o8Pj$2?G zgGlD9Kgqr0$GNsux9-0ld+P<)QNNpf5UgF$`3|=3%42?lSG+e)E zDj&ZLeo=QUfRL=h0<17W25E@gJy27OW|x$w(STq96d;CYYXfeB?13I?!)hi}QKEGs9ND#XKnob5PR@P5KBucm_g_>5)=a02e)nfxp@VQLyu%)Q1D zQ2k&JS+6IXtcywM`P`83!V4}mWrTb%XxzRw&r{gQtfCTWAN03uo-d*ol* zJtuofNGq^bjv2Pu=@rQ4c#^)$Kc_bks>hqF>v`*In9ulrYDt@+alspmn&I=Vr=Q;! z4)umDmHU}Qa}C%Ifq7a>;vQHCL~d3k>Oum9VE=IJsopzO`UM^M;(|`&Cu`=y0YN2%_SkOBAhwIIVBe@_pw6P8P>CY$ zzcTmQu=2BJPg^mLxuQ_g%uR$2KAT;LY-wZCT3mY>S2-(BU?!Q7faadGl{?JP0?-{K*w{I@Xg9ZP>^h~V(tP{alpX|n(%8bB^ z2{xb{*55}c$@?p4Y-(WX>PLdH=7PZw&~#95{FS?j48BA@EM44VgaP!)r1Y6I8nlf7 zv)i4>J}dO;G2DdIO;y)~A<}S$laX9*w!qyk)QP_T^1&)<#*DYn<+$s- z|1?HzE1CD{(yKM5zVh*U6Md6|)S5|kxuvj^11pnf+g{@w?IQ@&0$xoey^{~FjrNIh zw)_2oL!3poyDP#f95C7UKHcAZ{w=Gh{|$zxfAnF|>N`o3y$@mzo!?~a8Q3q)hMDz$ zAOslO@cCCX>>S;$q5PU(7QNu0`{*d#F!{u5%rykY2Oj-Z`VF1m)v%!)Xz(Ij5KVMZG;4X=e%%Ex_uVd`YGUUEQ*)GGcU9HiK3iAcp#_S6Ex6h}8OG>Z@v;8*zix@JP!PsnSXmIN z>{_Sv6!g_m95!*fm)mQn(xp81C!{a+&gDbx217mbBOnR~KcZ%jGS-T|JqOdlo;uu31REn;=O1Gz zBz-4P6IF2E}>aK#k-8BJ2WUg zgcj9no9!Qqn`}p)cqCF$1=b&rYu#GNU2BkOAJIOE4XDm|#4NiySn(0QrR)6`A%baF zD8E~vawT`T;`-z(l~=N=d9InJBbE6&W%(VmNd3FhvL5eUbmreNl7{zR?&vu_xT$84 zxVzR5oz)(QUwc?K$?7yxt#9&4)5$==*e3apUVOf&j=xE~$nQNprAmcBdp%yefoAL3 z!hD^M6_eb&0&Okz1KtVsG<4V-@Akn)UMW6p59?^p8Vmq{ij~@0qeGM;)0a7o_`rTo z7q7gJ=gJXtAi&LRXO8+;*!_?2z*mW46XtUfJ%-|$s~-k+MH?)|0*_$pmNZYqHE5o^ zqS1kEt$!-A47z@~e>#&5wDLmhAPKRs24Eg5iWMlt@@kqxOaLF)GH^TTVn#cn`9=~f zgD;ypX=>x408?74rt@QECj@LcLC6|RW|f?~&l~J#T)^x^ZsYqP>O)}>ie%QObfX@X z;5#iNZF!AsW-}R=dQwH5O0<&q@8)lWa5)cuodv|9ogGOEeZf}|jTaiws#BfspWWUJ zxOO98tjPrD#a1_T zEnbRtSSlHc=iPx|l-qu(g0YVVQB5QroXMfN(+8z2+F>2Ed>au;X5Rs(AI4~H5#BXj zZ!KdB?1#V?;o|32XNHwV_48$pSzOS(RHNFRzTGfk8+6P8BiaUyqYyE%(yq88cv(h4 zW1vZLQ~j8P<{&Krxg4-Ih{XEvpJaQ@Igtzt3p+VFQsr(JX;9{vLv0P){CQN%A5`M* zceikd@W@&RIj6oUqNTl1V?{QO=91IWnde+g$_v(qz9XJJw^d|X1dCJYQ@@WO9=;sdZGp6M(IXd$u zMg#pvWjoT2+D`tj!4mSk@@?+&e6uelLk!*6wc{e$fz`g0FG6JnlKD%mSM~bUlL|!2 zhla8U7% zs6SzlHTR>G-Bw)s(R@UUTHXJDMCEjc&(+r(+{p91e8SJ-@j z7rWbf#WxhJ+i4Quj-YJC4XZo@xrx0vL5u&PX#;s`3(r4$AF~9utL>>_&JHa6gz zY20V1#sD{lC<(E`cE|}}F({U3y-xVr`KC(m{W^}^;Y ze_8!vAU($T-JDrzBYnIw*YZ;q`WdY-CZ>^JJvTp((XcUVrRjBRi+PJdYoj@_(dzM+ zvQSwYUrS5;Tb3-BbKb#i4klP@6b?KOFqeYzt1L#Hdi!X?2hN=;#-Ttzd= zDcXQ{hrOh-yyPHEc2o^tJ=W(@6z1cpbq*`wWI1wH6tzF2-xbyCUOKJP&MS3AP5+P}ZnF9N6Zq0O_r(t#6&3CccGT=CH9z0*av6#ruhup@ z8SAJaFQa<$w+_I&cL)y;dycOzqs%Wo&`nmrtJu$8ZN`2dqr03m_VxR=oo8pQK-|E} z1LD!f$fHud6?P?Ez446h!B~WoW51eH;y_vHEvJ=6U7xCllPe>-jds8WwZpl;(d{KPzX~yVp~* z|0Q+thal6Y=Zm6Y*nc9`!eah&B!_+~tq<@Wd44qW<%8)_`GL*rpc;dJ&1(4ZtN*dX z|IvJgI>xE2QYU+oxLxQr8Ai{hQ45^oSlWhf0bBqp{?=vm`msC;f@}d2%(u}rX$&l3 zZ>`V@0<_)XY)_PHPAPw4@_w>r2Q3Dyu+jjZ`5E)@w`N!#fa$?0rA&xQQmd8mlnq$k zc}!$Ku~TE9K%eck8!u=v{ICjB{efrnfBl)U;Vj8$?6A1(yP|Ai|LY3x-7A8)Mq-oD zOaG;+UikQr()YH%awIYN@d>AqQw$T(udMo0x0RM61kGb)&@BlByZO%K3=EFqjRVDTnCLz)*hUqo;L5J-vIGB@oeJ~OS(fAa32^V}-}-gluTSdt zrXqd!XWwrVP{-PV`@hVT^OX`zDa&SYuiqBD%Dpon_wtB-S1_9KuTDoSQqQDn$0IkV z07NF|7}NP~E}yf{cG0c6n(Hg1xjfK6lylLzz+O%Q@xGvlKIg1)7RA@5?{mjfkNQ%* zhQ=bwB7D;_BPxF2PI40jb3FpYWmQ{52FDyW^AyvL zf%dT5^_$H5D!R*-M*0M}9uHG^`L!0pjU@Z!2>&(T?W`eEjY^+-loefwVX}9iQRE2y zeNE@o{#!}LBM<6%KK}Ntjy4;a*`deF8-IBfntatHBe`5jPp|eSV^4D7k?c)1>!nj+ z{Z;N+h9V9FhU|}oALcv=PR!78YT2LFoB!h+ShbB3?|Ps+xpZsbkve;>ovX(dm>?Rs z+{_xnn`E}SG%#Vwx%wL(f7N7V$5}>vbo-NkLFq{C{Ah|@flhqwW6@DQk>Alqzh_!K zPBenaFdr2Zb?oXQ^&qI;pz67`#~A%+yCv z-6HXqY`m24P z=S}i|!Ax>~!OTA01+SaIVhtLc42aAi&ZHuG7*lUZuyJZ7)+c#&d>LOSrHL9w^?J4C zWMR?>wH2Bw)w{n<{Kp4EG@uOFYj}8D6_4$!klU~X;0~;X0Rbpt;r$Rzme}c6qJ`_` zH0D%%Q(Nq@H0IZNY@vIQ8Nk67Do;hF?SdPi`oM7PYWYjk!c8PHAgMtTwH}?fe-AOK z^i>u%ngI6+mW{J`#e$k>p zl26g?+-W@Ac3O=OuQC|pkG(%g7Yn<0PRnc%JUhT}(tN?<=w}l=0@3wo1uHP&(;Y3l zV?-7#>wlfa>@%myyF(LTj;xK7x`<&5v}LYS^E@3ZLkJz7JHE!@0(Hx$-DR=r4wEg} zWplVkS`{T3qKq&k=sFPGziE4ArP{3e{ZDr!(tT@w;7rbjcu{?IYjd4@mj%)vE6&W- zM_sr3ATMKbfOPO)?TSg~t;i(@qu&TyA3dks z0z19?dZoFdiAku{Q2L?lpBh&e96rfiGTn8pk6E0HV%WSP4WA4+l=#H+_)Pw z`B2sCfUIB&+=J6JlRg>i^PZ_jmort$fHP@jsk4#z9(suN3BF49r``hN9I%jJA3PL_ z0u$r&M}gDWQ|5qhIJ-5P8GEWY^zAb&3qXf`$!3D*7oY=sikg*r_E>_O*v%OQXt6g) zn*NY=`4#I2r%ut>QUN@5VDdq1d+(gPFIW1V50>n0 zVJAM))y)K1!2N_xCY3>|JwitHqo>Q)F@qnaEls%ImkV|9P;Is&fh)4bH0N(rG!R?l zcBmz}+B5pmCgcx9u^m(838d3-@CpPOZdj$xW^-3rND zC)kg2beDa5M^jm}RJkHMOT{{=GlPLQUtwpZL1j8hjPlmUuVWCD z;ICPjkHIMrhBP`Mbgk=iAQ@kh|#M!8s1FT7l6qEJTS(MF7uIPcKWEL z-*papCj5WSbsT&@RBAP@;XJ?d%B|iK@-R@9a7ts7WcPJUVnsSN+5W&aQYWH*Q_=O= z>Oi0UCmwU8!+?=D;8?SZ*^(b8zNvHn@rvEDp;y)Z+);FIkFQ*0}b7ju7qE%9XrVyS#UCbwL6Y0|W; z#`ONx9pQ(wt6}`?_K~tau0vqSTkc2u@`_5kkqW0{(~@$GRC#4(?e-E4=E{{T^}AjU zd4bR0du{v^T=O@LKvDXyV;RZL4dyMriS(E>N8GHx@!t4(^;OjqOB2^YbTViHkXS8* zb}b*-wqO`H8Mp+3ePDqio^e;g?Gykm5;LB|r20sgb&=8rM z!B<7kWz~Uwf|VU)KiCUWA(b?ckz><@hO^OYWX4u2q+3ml{|yB+YgHsJ4lE>Sf34DL zuxA0_RP552Aza*?MwvmrWNVa&kG^6WJRo z^X;lnn?f={RnSSi%W=cBu1`zp`_Wi|zWQB_4%S`F$Y-B+&+a@hZUDS!-@cf3&s_>9 z^6XE}SZd2;m?DZ8gn_f+zEGViF7epp@Q|*|t7%twz^QHJ(GpCrb6z(KHep=O%c&RQ z-%xZesZ}XWG0-X7*>&Z2Lgz(uv4``HgS(_pDI4DBhbD~F>hFeS9G^L3e`;6t)iOJj zErYRRl|)ageSUQ27t120&3C|^sx7A?v`?!(txZi4G5>rz(G-g7lxI9%{1qYsjy)ryHZp9WK=z_RtV4Z9&hMy5?F9W4I+QOEag(W=5lQJ#i) zKFX6K<QQ`Cge5`CI{6qpLIYxvj=i z@0Ox&&q5(%frwW?dUEG3U1gT%U}di4=%b zkxp8oq5zJzR=7Z_PymbO)|}F2+Jk-sl-lLeLYmG{$2Oy$;G-n-vfA5NSE?R974ITH z=60$wL^@c-Mk}u{;$K%(WNr*mURU}SZprm9eMmOIJhC}*ItI}J2iv1dmA->1<&zsv z@SM1oXOeH;`Y3b!%8{G8$1jePDN(nHP{POTBN-ag&oG})L zwld=qh9>pElmI0G-d*_Y48*0(8YuybWlohZ_-XprA1)OjDb{MCJcq9n{y%KJbyU-V z_y4~!0Ra)Eky4SC2I&y#uF;K@NRDviKoM!djqdL5oJfw*NJ)1ij4pqBf8zT+=XbvU zY-fM%?3}&sx%YYR^YLUFS$yeyG*WvvK)wIYA4!G!n;sA;o#*)30&nq~fRmCbyA5$T z&jrA*`;cq5sj{f{VoBRRb}xR@JU30kxyg0bX1&^~@V2Ul%4r099{-P4gc1voGGUmt z|JX`}ovrMTe)e=$%Fj3%Mz8Z}>)gkT%emVBBrY_53}*;jb}2X7xi0s<%J*?RUTv+b%910} znW(col%PPT<%Ujd7CESdM6fb{IKD0BP*c*np7*pJ9@KR|k>yHD%#GTiQAtfNErSc@ z_b{_di%!=M>MHvOC$NwgIq0_}jEqdgm%Zdt88BEeHIQafWQLrW-N{n)*>c(|#1pQr z)v*bgsg6@RSXo!-2CL|(f>RolLfLyzk*Wq(Iu$3Rwe2e7CuRW+5oAB=1-ZaPWbu0O z@SO2(azrW}zdQG+0Hu>7Nheyj>He$7~*Xfe@hmg%28<#ns1wn;{%iC4iHYb|6uUf;u5P*o4NAG+!zr@aVpBbBb`j((yzDoYyux-u^wCi*bvc zhWc1p@lHf)#s;be{zgc5hs+E;&!Cneq8Pr$!nrbBtwJrWp!|b{4LYZmk4`Df6Rj1r zUnd`Gbxt7t+T(P%4NVc?)^PV>aT=x%PZ58uQR@;raU18dFRmlxrxX&eFs$1(N`Rsh zcpKTr?6CLOdg11PuKac>-}rt4fx7un63?BQ`=?V-MOtFbq~%axYj4-41G|uSi|9Dr z$vw*-VXPF84hR{(3b~0z+0Qdp=W3o^>{ux_-JH7lWHOBTRWgV!e-oY`x!YM|{C63= z$0~iL9I#53DWdhi-M42ERH5J#cJt}D{Yq=#@+K@?d{1I_U$YH zSbB#5wag+4_5hDk3B>$pndS>GK#qa88`1Wb3x+54y$}C(m2jqte-rN`Fb!Y|5J!s1 zL=FZ$i`GwT|Y{9+@UOb0tEV~=W_I)rS+dWvL zg3l^T&Ami5jdvd14Vzn!w9}vkdhR8!z9ZZGtSuKMu_r}07NJlQN9Td|ihXlzVJc?m z_-9^j)NJZxP&pQ$dNdUu@23~vXn4g=gUX~T46WTNdhea4V$WRkUZF;1Q$zQsf0ky0 z$0|`BTe)0hJSAIDU<{$ID)@W)UN%^HQx=g&?&z))m%vIPPCIM-v{Od4HnLtYAX|m( z1T5wnoX}16LB7T*u}LNr!(YeCXRbOfQ2#ntre}ai53W}vzY|$6ViQhTkWlpeg=$an z6$9lnG^fh&WY?t}mxlX2bKwU*Ufv#dzTa0Qp0v^hnd9fx$aQmFFa ze7&3~rWX7?sc`l5C51>PAOH_jv&G|Kyt;d2U_S3b(G8-e^4nnEVCNK4Zl1-!f4os7 z8rOwqCTv+PhOFxdZ@#3+qw*Co_}+%TYS)?#Pe!Sz>FBFOc$h*pP}Um-^Ba2*vIq(E zF9l!OYhY4hoMBd4-fP=opS2!VPAlUOg?SNqfx_6SRSE)zO^O8g2W_kHihpzTs0`tS z8xVR>Rb4myCKvoYqa>}{{K*aW2YODcaV2H0P6^$ElM?5Nut?WMw9W>42;5sH%RIuS zvs%i_BP6BEUJ-PHJ?+*|{e5fXm_jnIiZ<{zjj6FO6w6F^-g-CH21R{S)kp2C^{9_% z&)4DD7fx=dBE(9!&v-{>BOq6XNr`Vn<=M%$IH6sh%(0n8>&k0ze%lZoJ2eATnbB~p zXhbKZApUEsXq3j-t@xUdt85!7OCEdR`;=9MZm09_S1Q!$xy`@Eg?t=BbQDH>4p`Z4 zh6#)hH>=z|s|hQjr_r2SPPZEZLf2(+DV{&&7Wf^?0zEe`PJfS>mpR2?O<0}F_iM+M zecO?lqUMD`yCUg#SGr52o5yb>KZpC>7Ujl>xpiWWi7L*uqyB%}4lTXcWqzDzp`Qw7 z7?-N0Q3qiycWy^FSiFR#+i(_020sq})(!VDz)uPEn5{52n0Zdu<@+~IuS-0UWkN0B z7iuM>K`V~zqeH+unE1Nrko+@CEFPts!L|<6??y;e^^V?P4(M9t2*I~BWMKQs)7=ZB z3G@)EQb^-c_mlf$=+|%k5mM(p!$ge4!qxW2GX&SLCjqa9uoOlnjp!FhGHhP)PzLbb zduT-h%YB{g>#4q}FKzixy-u?qt+Zm_0UVa>yfM0;{BJ`hoc(8Tn(&K2UysT2(j9Ws zD(5`JVic_p7NAJUxgUL$j+_0@Kz&V&kJ^AcY&PlxwH5osx7m_1iJZ3Hgt3Bt10Sg` z*Hn_zuXE|4G7MOQc^_g%S99_C3%_Xo6Tthav5$XzXYYF$AXPV?ZwQL)F0khCi-;ac z%CsMik_36R^`J#<&7e8jZO}YT|5_eHz&>gw;K=9vf#2g=6tdY3Cn+M3+{RwLOYvZ0#qYaF z@7=?3;ufE)&%VotVRd#rc-YR!i1ui)%xmy)f+=#^34FMK(lpHJYL3+7Z`I4MCDMD6 zS$=y;w^2aJE*_X&vqf3@+$AnzRRv6KQ54eskxOkr&)Y7>BfiG$2G>}yQ*V$g(ZSKb z8b2^nhtk3QL&S+4tK&+W#PsyW4=M*+{a_U`Nd4=2y&iUX4rQ;kg4ep*s~%iY7A4m9 zHtutzTqEWs8;+%V@uuT`{5U@0o4&d#_QbfKiV^ys7`pKQ*$n5;=ER7pIklF z;Tke63po{}$lokVnt-8sT$-J>KHBl}FK8H4k1rU)E zArc$(pu?TA_LYLIddx=hs1fvZNSOpz|B!*XLX32=KD=7(s$wamJKs31-I$ps5}c%y zl~acp-jZk7-gwpI)MbWJUtKqitI^?y({?H)W2o4~>t&1_^Hsumw6AY_P>{3P)dB)Ox@OWR#(Rh5w{R zJ}xW zYW_J$eMen(Op^(1tzw2CX6qS|3QTa_=H@B>^QT$iKAp3Q5=|^v51$O)ck7HPlBFs} zTEFp2dGTKB0JdNFy|zOi)%!t+en|8XZ4&d)B2rpo?%39N@ok@?k`bf-dwN6KDTkBw zfevEUqe~Gy$cnq^l=EP?QykW#6Km+H;nhU`ZS`(EL+; z4a@Pz-y<#jAAOz(+Nae(jm6x_NzYj){(!-)sBY@s?(_BXVIwK;`i)2X0NDp7tt7L9 zY0vY@%Y~hO`I2J!HMV8=$AV83MQy#0oFE(?_WfnA7 zb!o*l*scgAP=!nTgsa$djprnXGIVSdZgTLjTg+l8+5EhNDbZZo_iZ{{NfyhDLPM&< z`rgJdHKaB5$a?l@&av@JQZDZ^W&+Xs2Mamy_avBzRl+tHl#?H`1i(c6Nc2rIfLHAU z&?X7>a;mzCO=7~{q`W+R(!M5XIyt0?JSyJ|96e%anWjIt#l!uV8rY!Ou4|0H)kn@* zZ&XN4J4GYGq>YpHX4$J{@*Mp}MWLeD8be`QHriDO=1?;)56MF?xcFxEDNATPETAYB znV20y83gLboIpIlRnIM;JJ8CXZE#!c%PI4)f&EgnEiaGo*sMy^V9x>fMho8oMSeDrI5u~?ZAuJhQ_&E86#sav{ymOM65A!SGQWK@btQJG_8nxwt7dk?nZ zN-^BFV$kB@su%^mwKP90)7j|d(mvUj9ZF3uzZ5BKPF6`tENs2E`dQ#lxUf=z# z72bFs`^*VNX05O2p{=JWt`qSxHk zyfmp)P)*Fq-$OTgce$h7`Y?LDdGT9f*5hl!Z}t~0>7zspwZ#9)w#ObVOaAASQ&AoU zeE%0oZt`CM>c2sFN%)q${h^vLat%TEkO9Esss~yia-3l;{281lKwXh$+)E%O%_I)e zFzS&TZw!z;>j6f{sC~dP{dabUbF+2d+)5{qM8g{RW8drpe5`M76o1LVo^|30>sS&K zCY9GJgh#+l^gn3&#?`g8yW%$*^!!1KPaR|;lX`}iZt+g3*{nbM=SWK#iekeWiP|a9 zYZ1;)PL_{=G{=ZDK+cNzQ5tC7-8$CyL`KlxcJbWS2uX{v)yRW-CiX#sZTB5Dem-Tg ze1^$N2TJ+fCNwdLH-~GU0{h2eC3|M}g~sccM$EgUZepCn%lV0 zi?d;;Bj3sEpV@`eK>*24FgW#e)J(k2{p@kMNsBoN_iUN`>;(sFU^6A!yds`P6)aY+ z)KiNA!{L>;S4ODR^!zlMW@Fw`B`8Ei;>oI@k)3r0zJ`%Iw8FJRWsA~rpzS4Mcu-&4 zKZWo|yk1ILPMZ-sA1{vuCqEH5ev}BKq8kZLsZnB9R+a33mq)zGrDD4Maoy2MrGe5z zonxx2Tj!sWi=)cdpht;5yA=844ptxH!UC=aiYDLHh0?UyR2niLN0K1hYJYXgL==alsZng&mR3DU zYLwYIu8^p`IG)Fa^;0MHi62X#RW}2CRpF_1bF(G~*9ZFt;`#mgP#=q6kF9l1s7i^#;u~|OFwM!Do>IiYYPCqG;RRQ#qVTPK+PEDT zxL3lS)unoTbrbvK@d+Cg6YQuctAZ6i!~_{wo#-b zHJVU`3kMaCuSFoXr$pIbn1mm*t0eF3x7M2>Z$NAF4DNda;t!$z!afPKuJaOHX^3L< z?0`zl;N)!+ZpxOGdH8rCw+?F3npur&^mbs7T$o)G!^*<$=us2T@}48mG)6apltols zS$}>KtI&AGtg;O2j?cVej#b9OGwjrpH}^IdMc+Xb)z5f&Ts+#spvSpe?6%u<%+X1u zr(+Pfn@(xH>=Vs~qWyKqgh0Ms35MZkWyZX{5-Fz`@~UTE0{s|YMA z+LJ&oI9boG7e|it{#T$5{_of=MR~k!*n{c_uK#3R;9p8l3`l%dLld!e*~DXyYabyA zw{ezV67#NT8*8`%!EB%@Es~E`E@)=TVJpTngLAtsJOk`Q4T|e?1wl-?dht-Ok20KD zxxufH^nv_XY(Uk+Cfu?duBu4gP?&^9@v)2OHO6b^%a;fLWJ>5`C(VzUo=g5Qf1QymBsxqYx}YiGv* z`;msia%^KaY7zi~bG!zt?@}t~=hm9j(4dF>imMSbf6A~f#(H6;Fn}NSz;RQtELk|G z@~23}`D3YbI_O;dRs``}^~g6y=)M)G^BWJ&6n1Lb4CBIrTX?j>c=CwFaIUOvh(BR@ zHT{RItB=0eMDLFo$uVB*YWQ9MS*w-saJrznV1afsHJa`~lzz4`kx1uUn3;wh_a6Yt zEugVeJe?*aF6Q7-qbhUkhJy`7>S59&7-%$Wka50#AOZ{wqG6$36hP|;A@&&hyu!@S3|R^sOg+Z`FjwVJVATx4CRnTk?jt%aazh2W1KwE1Z5Fh ztxUeZ7L!djW#MT@n5(Uz)(kxVLNy4a7r;QB_6$s$bk@aD89zZ#>NJ_FwfG!?+tP`9!M}g z^y&)AVW_pfV%mF4YRlZz{GMAs!|6vx#x7&u20fIhHjz!dc+%`hUjgN@u|A($x8Dkn z>(ny3;_ij+U~!B3`o?kmx(OUyj>S4ZsETV&{?a23zo_#*Q&zBT&q0_xpYt9FPTSp^oCdGJ zGLNYIWo+w@@Y!$~f{=Q^$w-<8wY&1HnbkR`+Ssvz@lZ5X;?~?chgSi{)jKA>0M2IR z@im^ck9~pNOEx~fw}8#jv__{e@59tQc~5h@AVjuimDP^j*}6gJNKJb&N-*f!_5RB& zR=~-+6xX2;mXJUGVcKaFj!Ge|+~C3*Tbz&rfGod+1r(kK{+z;Q7QCR;(E19H zMLrM*%P|z;2qNvXfUpOnpnZNzoNeGdzyM~5q!BO2@6O2(wI|E5?QLXjMpVif-nj6NDMOirXm$4~y2@c#Z!Y8G%#L)w`Cs9F^RaJFOP1C}R z>lnp6i*DLe4_`2*NcuHYz60AIqT1Ywsm}?_OQDoo0y5}KL58^D*(ef@bpp=jU@?S%~Mi( zyd#;1(6jdpysm4zLUUEv*xuGX^YZ2kDalVqX2z{{p;MJc#bJld)0v}wZn!e82nJJd z&e=tUhjXIS0;-2$Q?kvs9zXbE=?r#gb_JW7A7ZbgvyIg>SgDhs=-ptKb_|wY(HH5| zOIA+4Z+C*aH&_0YC=A7%Af$yA^CuD=eooSDpjF1Y)=d!wRK>5VwesDKj43m7;@8y> zEcs5_FByxr+Y`i6tAgQma<~|x`d7Jf%*D+d8hePJ5>j6l4 zNN<`kI|3`9RIs(FvaYNZQJtk{bajOq9@6smt_X59w>vp8uwsb4(_C@BEOqp*;}MkkFkbx(7T`LXKs?bC{b?pOI}wZC38O!geExBj+j z8KtL2$EcK)ig-SG-%nj)zlYg$9d_;VO{-DfE$WNrSZ z#CS(x=DmK^a=Hc*y0n;Qj1Ic1>A2nD+1(#W%Z5k=r3~NP?ugxCEcU53&lX!NC1r0e zuzbk>3fTA`V&rvEKY%{#x&Hr(GmX3?G63ptp->nBNCHmtT?X(#ZcZl2ESN(EOK*M# zkOY_^c^?P@QGoD%keMMq|3>drDw~>;f{ed{W zPsI-@#^-bQg{-j+jn{k-QYuow07f6MugAD&XE{3e$H1vPO=^AY1uh2f(ehq`qA#yo z-k@ufYxGp5c{#C9`S`E<(uUc&sx}!C9;1q(NXE%c=F~dqtiEKMe{Rs^dG>}=o%g^8 z=hm&jawEesXP?Tcf>!lbtH4%4xjFc?4 zY&_gx`3e_pkC=$HnmRUaMb*u%4=ZRv3bhdofJd5BwMVp>122APoPw%6Fj#F~3 zVP$RQ1`PAiRZ1H&bK3;ofeiA`ePtVtY44xqm|UILp~yoNiI62V%0==U6bX726R!C& zj&Thc?kvS6{%BJos@1>tSv@W~u%^mf4e_Vg;L#cj2}KPVW}&gd_xnvw=|(x+W>rMy z!JK`Cj?1-~h7Tuet{zbhmD5{|YL6O+%#EA(_M2CMj>=akB~BghUXSU9Mv~as6Op5? zyx)}#oSp%yW~uoV2RixU78B!%?2Kx2Hd&z zdoDg)?MmF8{wv^cnZntyW9CR#%vwul#CW7v4ydR`VJyZsN`LLRa0!s^OHSmpl=0fdVImgwa*5#I@jc_GLewIY+Plku+T4d zd4gIU1h2TZyTB^BFr4JZ{3p!r}p=E z64=EB#B1Ay%NvTz^xKVVHaJWYY`q+BH15t8{nE|7?fek)^xyb;mvP>Fl~H1Q@kQ{V z@+VT+`>XqrEwnkGz8vxi+3UM==;Bs}-y!=E`$bG3WBU=5DQuq5r*&h`$7m3#@ z7X$9a1?QXC>c}}~z-Zy=pfG zRIXyswN*eF#_<4)mb)nXq;*l=rsyNMR3N@}^m{SWtkk5!q_mu9+VNKi*jP9yd1`T{ zn1X1C@mqpMd25G!y7221+)oDRTKi?-LS@UU%22BZ}+4f=4GyvP`D`$uJHGsp18_$)@rJ{f6lw*^!SeBLwyBklYnb(>QQ8 z5*h0>86LpX100^6!p=?$smzgc{O1qg+IUHFlGonD3lK|smlDGxVBsjp?Q0;K^UCli z-(wj%zc1DNF8JMIfLOn&1h0Ze1}9DYnPu#I1ZA=Yimazr^V_P=zCUzh8v69Kw?FO4 zLV}lF)b<0tTnT3&4*Q@fp9_FDz#TV*FQ|;zFSyam%VTnJK{L2Xg@b5+Mwb}a}DeZ#CRoLd_KBE znUHU)lY6??6{x<`y}n(>4G6p>f>i7ymxnNM5_1pM(!b$L!vA zH*pV53Z}&rFB6xp$37z{A&)7h<7A^Mxr^qloJ_4htZDL~TxCa~YppBUY5P+ex~2## zDG5s`-HV?cmykx4&7CIY>w_=AANA%-SY1!XpGEZwr73@4 zOV<)&FkprYTf92 zrH9ZUk6!0d)h_;|%x7wxD+D1yr&c}TWu$Mk-$DGcDJUmH6z!`5uElc&LS;Mqm27ix+E&S)2eCXldGFMLXt1!f*YR| z@yNwS3;%YQ_n04oZ*d_36$U>?ygBb@vlPx_cYiPP?Cn*!?%XUM?cKC@mQ_mMK#7+U zry-G<)2xYDzHLR2jGyu0yj!qNC&PG)_v{ass zUK6C{4hL1dm3zGfcxb2pDIR$*{wX>l+rGA$bpt&iZx>Br!ommr^Nh>?gsm8=thmuk z>KP#B#YdZ>lx8wG*LdUrO#nNR1oa&+2jK4O=g0L0Cjwwj$N47f(JFuxn_038;&Zqe zdZ6?ZvOZ+VZ~-Ip%rQH412BwY^VuJ{;dr7;=LP%2aZB7so@&(* ze0ezoN^p>QGjB^@DwqLUP`WrhojF$m;W#GxJ=haMCa-;s97YpQecF~~l;PL~WYSST zq{bEFbJ_frEY3P)Eb4?x0bV>|9RaHEnI3v%jmF@gwSL-xczs_(0( z`zP5%Jk1@<=gM8oFN>B(819|hnPj7BW8Fiit&zR1zu!7MZu6vsp=b%(>C%Y_v7nqX zW0t(K>B5ld%ADqe&u zy|*RZUFWyr!wrM@5EL$13Co0n+X!wySdZ9kGebGGBRs<7pt5+Eeb%8qw>eFrMj>pb zER}l;LtMDaf%~B()ShWHfys;5wpZ^Vaq?;1j+0^iWs{@dB%Icte$y%r|2d~E9wK~8 zPiaF2w{*HUfESsys93}{DD`J)2M3jmbI`o%+S=y%Ob6ORKWU3oc&3OvC z0L{B;tG9OZL!O43nTPtD(^4}%dx`AH3WX8~Xlfg%xNFKeHulZ?QAD>;5MQt#9_i2j zDR-zcSV=N@Tf5n@n8j}=op((Z!5Gf5H^9E~#<^uY0;<*?4D7kNhVuq(lS&2<`jGSo zb#q<3)$QbY6{IQC;nEq>9yfgiDj51JBNu!aHGgMxMv}L2sLJLr7fT<*=0SdGpEq47 z6KisxD@n*8m9zbmDdI@H9Iz>8=i)0t1?sxk4#(Q^dda0PCBdC#~Y0Uq7s_WF@=FnWV z1H#3;NiQ`;yl%=LKD9LZ!73wKBgOfCG{NOL8P!2EB40&H>E;bg1`etujC?n~UPe zU2Ii=<^g3M|Ha|Y1|>jX@&KAFg6E;!55GU2dC-pqD^m>$pqT1{E#1G?)40^avn9Oj z?dg}F=Z_qEo>hegDH4G*P<2ifDepI z?7Mf?b6>5m-Z01{>(D%}#%6fH?mpFSoF?tQ)j36if7B0tG%I9XMhCyDnq=uX#^?5l zpe?o;&D;V=ozQJ>wYjeUz+%CG_0YveOs+;mX=)ilV?~xdIo|S)`=v1)Ji>PHOlTzHjis#A6EHhD_^0a^0M%g)aYEe2 z>juLqJiq5BPF#kgRh@b9uEvPvFC1f5PQeCIw(!_IxbQ~AaY%Dz>63Efrckd%%d(to z2kp-NNWF6KbFFIX5>Co;&Sc(zJO#Kqi4pyHc#Q{v z=?~75SGfw)Ny)8n(&IAH@c6Of9KDjf_Z*e+G{TtJv*b$G&c~gTm5Pjkre|+45@IEW zGlkl<9htXL(8E+cjum}AzN|EwcN~^eoN0~0JmYp6JHnI$oXhHL>*4H&n(VT?gtdWu z7PIryl{iF-ybNNH+<;G)k zWl)3R3B*wv@hA7+wwHlDh@($;lJ~7DpiQB?7ymV{oJ@Vk_8$Fz#A0iFYP0p!^B8|Uvz^eW)_10|VE8JyCQ z-A$WxJz^HQTFcwD=M@3dfK31X0$`3XG4@Ae8*e zr$mRJVr&`oo#Z~_Ish-+w3)SD#yLCg%{N0DNH&8xk&m4CWhh6FyF!U5MQT{K*U{NF z?D&)K@UKBG?wSEv6cD5@jyX^UO#(m#t75O4QbcVY6VxH+bu*;^F?HdKFy+k{_jnR? z_gswNn$LV(YilbP@)dELjhf8cELx|S-)Xg!685oxRcam^%l(Hp07;nJ_Tx{W?zk<( zMeVSfGLkC|noSsAoMt9Waa>}{%sNvmHb7bQoa`p0I+qndVzrnqdCHp!)We+*Pb-bUC=ww(usfMgDDs2jFsE^Q-CD2rH)HJ%10r$ul$^ZM# zaj(2F&xC3zoti75Rw^b9FQtqrrTfNy6jQXyU9>;QNrhq~Q#Arkttglfy+>T6G^qI@ z+-5Uk4I)y!MSk!k*W2%dS3m2Q$W^LO3C5RwkkB40Vi%{=C|&0dfZC7Dl=gWPsL6XF zO+IQ}xh=GmQRd23l^0QR7Ez8QpGRqgr{H?_{EZ^4c1P&Eo2nT$9_#6Y0}pLgR1*5& z+%fE#LbmFE`8y#gXiY5Li=CK%f%fJbK`Mg993< z;njwSFm$-S}*oBVQ1X& zh*U4;BKenkNzrgxE>6nlIUkK@pWELe$YUw@lc6h?8ZR)f*M%Kx?cyxupB@#-E=Ghb zrsdq{;rc$sS{+kQwkU+00oOSoBcjg&+!G@*#^Hgwy%hSlh;P>T)`UKN6m&{#%Mtxc zj9Nu~g$|9HQX?;*cr6<{kdc2Q=h;p{S|FaA4X9|=a(0z$*ih}S7tmPh z9iqVn`XBZ|GQm^Y;zL>Bo4Di6L&fwy8tGr*r$LYf8y3NLol@$ z&=0;QiX?8Q|Enk-M#9)2rptg-yxD&A+%u;crwO1g0XhV>0|I0uuSYgK8k~1Q?R3;% zf74=9(?Nz$=@a=+akFyFWS;XzNh~v6YbS6*qi9EaZh>%sD0adce!58k>xN9xxo7Yt zmeJb04{#u%vfTV!?Pg2YG{&zFW46H&(=P=(B|l8^G!0MonX_y|GhP9-#`h_Z++9g9 z7ntNG8C#!}_0SliM#7$9G_(Dye2&e}eq(Vhk_G73zfs3pG5pB4n|;9Hyy|Y7*fH)q z;OWd~H2x8#U)n{;7P_z&fA+_=g3<0MiI`hHcYsd9@wl*7>_s1R>508_Q+%ul60tS; z_EYTB*UrIEjBDF{IS{i*J#y6X_FS#inyuJhuwdSHAZ(2TS3TLXTPjyQXNd9_ zGZCs}CkhY4PMjYml=RG(em$C5^_l9r5Gmh?ECEG3--NJp4>;RmxIr}m44mqTlCw9{ z2Y#ymq;mGEqE#8JAfsrYV`#lW*gtQ9dAOES~hZB;M|$vH(@F99SD8L6NB~k*>?TGd36| z(Xtn(h@fTXFi+AEWY7-qRnqKOpI*6-2w4ft&k3XjC&DOR`1n#b;1a1QaH=SBsJIto z^p%A%aw6kbi*s`9hMA7jWXI5Zq%pP>Coycx#T?6AY^420+3i)WSw)Q{S)CQI)a^!^ zJ!7YlVS$|)8U5qnklRWuI~uN&#lzew&Ymf5J<=7~f}_%Mdve{nadtYe_qbpBNn)co z`_W2Mh@x%-@x`Dy)clyeN;+#hyQ(YfGa=n6=cx1H0^gONdb&Z^i3AyZuld`x#bc*s z7&H)>zy33j_BB%{PtHo=P@tbk{>frq2}x>mKwa4{p9g2%E{zO}f8$*&uAd&5pJchX zw5q12x=eqS-?W+eAXOmD{d;^*-(lxw%IWG%*m3qO^|$+iikIn9#qd?Rv5#3;i;LmM z#owhuMaL%eC2{)S5_gA4#d61ft*4}lD#f1e-~Eb+3a zstC4m-7uddDE;I51cqBdYQQuHP@*BL13of#3&{$jwT)qr{E$sP`lNl}*LYL|EN~rI z1u)wVwxz`YwqKH{zQvaVc04)ljX=BG%WKYM)4365DFn=Uz5WY}&jSXYl33;v!>FH! zU9FFrCLbXBAQIBsshanp@{7(XV`w& zhJMfA(D9?MDXrPM9GF-}VZXFIMAtF4Iqa8op7cC8B&?!yD_+AbnYHQO6s*^ve~P4;D;j$ja)qn;3zr)8wu_Zn^6UB0|6dudB?IX9a{v1;x{2PQ$eMy z!moTjgpQYOE(Jw=!P0z_O0zc6<~P~Y{shFpG@NS^F^~XP*;F@y+D?SdD%IP4oZ=w) zuJ~p7OLMP!h9k*9XrxLQQ3M&+8)N;KQhNzbAWOM0@`rikv1;rIui4Tbe)yN2br`tq zz7ZA?k>5w5YzLMWE!n!x5nC^2qsDNisaA%~x?!x{QH zmx4rP6!XeF=|;cNdZ-T=j!h1*IZO#{(=_n%YzsiMLnx3LOU~CG)6s#SPy9|;)U%?B zygH*(J@cdsiyW8y*qDMyf_aO6#M?iAsTr#noB<5I!CODRKUq&qHAxjL{q&5E;dUj-0K;&YZpk>2h`9#me7Aj8pL!2ikw?H<^Tk8pSG? z3N|mwboW}Poo4I*{C0OvoeOMHbv~LcipgBG%D=OpavHd4t@{|*+F;t*h11Eo*{*9~ z>iB-~ccRte#swBMcI)&1ZfJ&sKgFPje8ywYcfk9`P-r<95f|FYZ2n#h?c~URQC|Lr z(GZ{{LuUw3OCoyq1b-Fi_hgHP_n{IDAlsx!^+lo=sE191QHHU}5W~KMFi(&K8%;R2 zY@niFsDWgn&1k^`tWseSB^CU^5Iy!4FN7ojrj!?~ z2N0H_dHxtUKgO*^dMPk{^2qX?I6&p)6iy|~^7L)D`MgH8;abL<9ej~5wp3yuA|N!T zl>5vv^&H@<@ejb8!S}|J!Y#HLhZH9^iRUn!B~oLbtZ#MDePunv%U&v3c)X0$@f`3s zOcXz6%zy(?^Ms_mit=`Dy2CD*`EPVJV0m;Y*}!r!vGdjz%t0aUV)^PSTdRNSoxx^| z7tYiei(Ax{O(4uEiVDz2O;4o0i8As#1M=0`GXqL$HbU>_&5>1-WH z0DU6Koa1Pq0ZNO}ecs(MwV65gzG!3yI&7XtVu_8x&SWQAe(?IGjNz$l(3T_wM!)yV z?_m|hlF|0beD2aijG@4AhbiyBuhUkGm4SO(7GY3MeRRgb1=&N4h~d8v0nqET4herX z3u>BaD!1Zvv4Ti}!qaB5#M3!6m8bhHIGtXq5~IK!WjZ>rLX*xQnO$pR&;6^72m)Kg zP0yg#71h?N63=#UH4b&tM>xp#Xz4*Mx)qwZu5mbgB}*Q(KYJ7=NFL+ZpQ$~RKK5PM z#>$*4NlTQjT4p2|I;*92rlf+=&`k37 zu;H*%ETgax18cn$%~A7~g$|FX#wNABwbk+BG@N>Roba%r>6~=trPDRjiR+uELQtzc zg-EdZOC22veeIW0d3yen>(QL_DO%l$+Fio=Ny)#Gk|#1gD@$Jg{ZTSqs?yU-9s>qT z^JTxwPJ0YhiFh?MZ|?xnsW$wn&>P){M?pYUPU}3A2}Y;tqRe!Bv&z2wIo%RkBZ%T) zd}hGy(7Q}4cm*a}>&h@1Y-9Wi6}>W*|6ySOZ+Hil2l3^HyvUD!)uv4}Yh4i^(oPYI z$3ggP0UJ4Rc^wQjhZ2O0E$}23YMOUy0&7P?D&YPLG*=|H6e13D!lY8<`lm{I11?O8 zF9{DW`tNiyCGdlT-^yRx5Ym0?|7WdtA3y_rytN@kDh!qCv7phq(vq#G8ZVK|(6fZZ zN_pM&c^&yNjvt0zIH^xCly|x(>bJQ@>URXyPQ7kY=3HvjD94CJ)qR+4%Qp@vzjC-e zRpAQSvMc}8r&0cC%e(xxnArH=Jz{REO{bMI`JaPP6RIusXcBDDG1%4S^o+Oizoi`P z>bdRhe?GZVxdZ57))oJ!==cOfi74L`w+DoWLLZaM&=nznD}%h7#IWn6{&xUIq&NV$ z_SOOh#JX|+KgQnrtqK3{7vC5#Lcky-2l7^s4rv%D(jeUp($YC{sDyM%cf;tA7%dIL zXb=$Tj?w+y``qVz?sH$)`QiHqY(MRK?fK|a>{pl-M|${E08th8GVl>*hT8*frBew+ zU2Hg2gH)(0AZEKz9N3v1(1y(d|{1cL&=%?xkQSgY`4PkTkZ(u_qhWX>Wwp=rXK9 zvq48RmomEZ@0B;;ZA~&(9aNZsKG3|-L6gKkOtZM=U>D%eWX8Ug;S>QYKiGjN$QD>m zLyz|!dltAxL!q}3FC?km+qVE%^7=pvC&x-KClXR8$pEBJT08=97(|rxEdWoG9XEd2 zP%vXE%oX7x(^;)Qbsk@vKva^NoDj!jfgb(l4mMw|Mf2Ef<_jO)B;Kt7I1q9vB!j{S z$hz)yq0wRznvWG;(v%y~ek1-8#?y&b2?cc7(dT19$G}amK7bo>qd9y3rh({!jhu*+ zA4ao_1XQP`>eV@QMs9c_t`@JgzQBw{{Z)-=#2m`eZCsdVW3`Aaq2G80|T2jXB=p zIM2xi1pmKug$CNdyR3trI#ehCf`<}@v{bo<~kU@c`aooB`H3d=a0{^DZuJW z#QUCz&eD3JqRo?@c;h4m@j1nbBw8u-QM~Uc9_)KH`HXWX@xJbJbxh5xj7Jf#X~I~^ zDb?8YG?~?6#1k}_6Kb^JCE43U`kKAGB?)#0-|kg=yk!voT=yw1eTDHCG&;Ulb(B)A z?M10f%jyA*)%+{BhY)s?dr408HlwI+7S8oZR_J5(d`{DU%0tU+^ASfK2v&#w#5z^$ zyF34@YhRa^Ry6E0+9!8VZq8Xhr?d?In@z-()mLz@)eJK8aLo1=jqp?j_ALe75 z#5*2dC0~F}B-5-LIz#~-)ELFO12cpQ^e}h=J{R2nm-<0&bYVQ;D_i}S02&>3pdrl= zGx%$avMvD61Sc8v-gG$XC8-29bFj)N@ayTe4iAcHESTRWHX38uc5 z9&```UIr!r|5njq&!PlYJLC2#{Qpw0U9Mz0e^6AM<%tLvVo4ezUjjzZ_*qAziHFUG zhdE(7XWY0upm})OFgS+z2+z8Eg?KU0vF_VT2CO<)1HTM<$l8SXZfBdx!GO8w7Rgv1 zQT9vwaooEJrqN_$G$1Y_qz1rs4!Ev`My*rd3<8_syn|TV0Q-n6*3}o$o0uM*yVX7M zjn26*r!rI>n{d(bx*#s{bM8@Q!mWJ!9jE%k98`#BV0{tW31+|{>xzDacQB8{g!nnQ z5j4i_2oPIRMW_2N@h*uiDIb)C0B)Ek78b6(-~4X+U%1MdE7}!JlkC}pv^(v2R=Gon zkr?Jr^KqQ5q?LE~W^oK@Zqki1F5{r$XD?g%VQ(pV3*G&_G$^7ns$Bec8p%GJq-P|1 z8$tv8-}eQxu=EhHNDWTkk?l6BF`KjRd=jQnhdx)~UegwOS_kAR?Ti?No(!vN&FQQ4 z7^`3^q_1=dk4gh`-DAtI!p|u!hB}cus2bd7np3OT2H5* zLN&AT{sf-C=7Yhn5{aUJn^0ia(hJ*j@Z=~ubxB9D{{(9)MwZ58)TzlU%~>~Cs6&%7 zgB%NPt8jeY=N3d7h*rLPQ5x%|C^-B zRG?g8G<|ZLNtwk*`-8Hlzt)9;XNW_Se`|xmOofP^_V)Dj)cjnHv_5&oMDOm5?a(M< zW(0$w77v$le>={Ww4QkGE^YiiRr$T|U1eWH_h}J9;`V7WB*}5QHDlM!^|xAUH?m0k zS4&r0Wrrwr-Ns;V%75sbHy^eBbKZ!bZ~ix*qn|u8E^3FG7@t4KU@D`Z?&qQ$;0@p| z{39{)X4ixca|_M-M?$wYJFw`ftFXDS6tR8+KEf$GD6#vy#Nb5zl9W4GV#$yWd@Tn! z-2xA7IQzAU1Awhj!7KxpG*6Tshgk{+U;yCKuj?!WNw&jJj-2-YiKK(SMErp(C*&Ez zsjz%8mNoziVAsKh9)moW5o1HaEw$@F_0Rd5o10Io zMe>{~&>fL*fg>cJ6CM$6{p4LH%?{-TjCp-X3%D){xE3DHrR#`dZDxo_tOlF_lB0rX z?Lma!8isDi=v;Rj&#|^>9?J*R4bapy{A!Nxqf*O+J}0U80TiTFw;t&_N||;;04pf5J9f!i?KlW4(Jm5k~q3a zhNf765U3;)PL6y%tZ&nXFRsdUXj?(PVOWlV%L-ZIXQ@!ny@W^&pY4T&Aefc(=+5ny zRIBinke~AgpP%VQgi#vR^i}m|BN69!m2~12;S<rQXKpx$b(NG0Y{?n3p$urd(DNjS+z%Cl|qE3-s9T3S>2Id@v73AxUp=8$tDp)(ne+`2jrbplq>q??<3$x#Hl zx@69T>{yj7j*&%onLpRSO($inil92ZM7!?0%hhctT1cIrxA2|WaPzD*{$)&QNisyM z-b*p@)|vWSL&EE1=od>QG%+4OUc35?r$nwG{@GwbpXP8>S*pN(zETSuIh-$lWiI_n zlS8T0D2v~FQsYBpaVo8*kfAz*5+E|JX@kAEjC{m*1AR^x14gVN+H75h^++~&oh`V!N zx|=;{`&~Oziir{apBPFXi5wH%SRFZ2EbEU?2{zTjHo^@dFt|z3@vnj z<5L-1`BT!wy@A)>f)<9RppfcW1(rSeA(6-00gkh{)p#WD*PuJxqu{v$Y)@)&mzOcLgZ=U^ay`n{oI==Dpcb)z5hkb{| zJdxCc@l5K2vGSSy=_Q;WTRBm`Pjkpx&bDgGy^Hy4@5#oMz2)qsXkD197JK3x!igZrlF2fAhAls%Q#}1}l{O9KFRloMwdu7uM<|GZ~)b|*# z^OUmFKoi9zZh1tTnRi`c?kN~9`AnA+e9ldgPs!^l|9euBq=Ux7tG6xN54;j<={NfW zK>?4xz{x-nEz7nbSiOyW_Ujwi4#^IaUHLQ314EA5(CMBNf&Oa@32EgM=hK0(+5_+W z%1M#UR)r*7&h1U6HcT-OzF{)m#CD0Runs2m$tlj9&)V6{!FHEnf z@57Gk1cjT!T4StDE5DyKlT37q@B~KZDj(QMMq`^Dk!nUgDj}!U;8R2CG*_6>TNpYx z2bDjje*raPAmu3ea-7SqA5CP#%$@sptvIpsvTCIAt1~Zc&3F6t(<&U@0x!)g>(0}p z`ZxmZky<&j_*MQv*6i}(6t_bAUr9qj@zY`DshnkTm3s8w1)9ku-8H)XJ(&kiJmUY;rLi=&E{Zi6|M4aVhl8 z(b0lND;$L4eAQLwlvyUS>$KX@@zPd>>S|&OhWS*a)EYQTqY`X>co^M#$)jc?uBzUT z$S@c99QsN#uJ$DkWzFOqj6mv`r zmLv?g9p$($Vpa}bUqw%oxzBw1$B=FJcJU?5du7^XbS9h-q0Fsp@b~`fZOAhMx{)?I z`fm4sN~)saG!{4pg`CQ2ftgjWDO673%BZC4^?)3iOi7L_C2FX)8VB2%qJD*>1C9^w z@LBddy66S);vkJ;*|nLfF;uW{CNop(y0GzS+AX>w;H}>-G^gk{WLkz?6ycM!P|@=J zU~FIE$JY0k0{SsOinf7^Gq+WAwlJNGKVFq|4$TVD^@}AkzYoV5*)O&OH+)W)SH!%n z2Rq;_Y`36tWbvI3I~E07%){WSi2kVL=UQ^T@37Kfuw@o zak$<96-Cn3dFL=n5!W)I|G4)O zy_M#l>~l`$^Yy$~GA(~Deoq~Y#RJB(cgFe3BQRMcx^5j}wP&+arFGh4v_Z!zy+M8V zI-DaSw%+Wawh+%-ExO4Sqmc2CF!%Wc^U;xeB7O1$w~%)4Nqb+6c3ln~z8ozMu`sez zh$n&{w;uW`{dqXx+!6@5`+Yu)GU%k0M>4&)j&D7RP=Z8cvK;p|3MZhbmS=1^4L z{&}fO3lY!ZRcCTL{wZh3<8nV+GK8|@yl*wl6cgYi=;xgo;;N*f<+Io+?IS4tT2}aJ zq^mXOXBF=1WaaN$wW?2}X{@OpgWH|$pJB0a`y?rt|FO1i_NhQv)5pI=T%&bXrbgTD z$=Zt38bguAkNLdwr8N|y=1eHRd^2YW>9b$c2XAPycC&nRZsog6VFg6u)h1#+c2rBb zY?Pm~!KmBzJ-+LXUtx*2`05TCS1w9dgV}05PhO7a$)_Ga{mXC6JQvzDH(V72JB>_) zj7346{?vE!MR2GF=;5eijG}4H>S6!LJV+t1DTbX7F^FFBZ$_#k@ z`{h8#pVH-LEiP!{$N9O1PEN8Ggg5N5{bppBpR;Ni>MC|8cD-7P!&N=MbyS)Y!fzwMoTYgNB z?k8b6R<{{b|vO6~+Ieiw~GsqP9Z z=}Aby^AHc35`h)X*>sSmi5HdkQ|&eM(f;>n&WG_X zgFnUCpt@wVWmjkI*dJ4q@!b>Ynhz7$ z?gRQFi$se=FV6iO>?c;HHz1#3?Z`}a$V2)EV&k#l zF*(|-)X9N(b4-w+(EO|>_^A+))Hqd`jHbe+W&}=xz_#trJhfTbe~QiC*fK7*M|UGKpqobO#%D$i`iSVlfBwXXguWB7ONj?3R%p1`p2`%)ao z9xu6d4Wk~nrBmG+6As8oik+Hft&Qz*1d;4p6M|pAsTIlJBz&+Dv^yP=()hq+|5F#s zg!EZoVx;10GFr`7&|Ehp%V#YUKX4t0^n0zlCL!O{5LrPDnFXQb#uwgCP_wByygJ=H zimUB(mN{lEZZ`|^!t;zVcY$6PyaFmVF^hw@}2xG z-!g|BP90rpCk)e0bTanw`J>Zc3~>8xnMM;i#D+GOD}3U9q9y327;7STEMf54SXy_q zxMsGe!amZ z<%b34J%KfM?+A=r9e}-E(5D)tTeNW(CT7!O7bddz6gTUBIr@Qq7?5+^A23;VzXWaa z@!o^MK;Vlq#|J2mkuU;%;xHmgF}?*3CSBOmbayn8^d#qVi>5qecOY6gjWg0Ye&YA> z-tgKw{>tRXLdi|4oGIeKMlV{ zTjV?&94Ey_eCo?#;V^+eIjoi5MKG&BC1smWrlyg#+P`4Y4^e0gqzT9ne0cJ2yz#%z zkbBercxy&*V6MQWg*ryp0QiHw2_5Pa#Sf0uAZ#Ue+e5%|ySMa6y25kZ;&{%mrtAiS~;UK0v9QIg&=x%PZ#Ze)Z1g=fIb zJ2rGNVMkhWa@AWdCzJ>eAW5xG!u8wuXizKj{5cLF#<6~cAddgwQ*w}yg@!kydi zez)5P(wi632~RMs;|IUJ0f-{*$B1%T#V@~zk3sHG5M31+%4_pI@e5aRtGEBG0}>m_ z&55)tXU@tU{f4?e^x_tS4l;yXd*2OqcD~IJcHeOq8%q;i2$TaMl6f&32)N&cz6a{$ z3B^1L#py6>4K$6iD>Z+D=Vd+$cmTL0m_w=sX3h6V&dG0r#RgpA3^xG5%~K`6b3C7s z>TytGbry4<>wK=UTi5&(`fZ(^<9pzK)j!ymv4!?-(#qEbMB~3&@ZJ}Soo*T~3$4#3 zZ2^`+n9hm;^F2`+f$W!d??sT>a8b4c>+p;3)mVG!wa1NCMvX3`yx=3D4!`@`AU&=J z+#Bjkf%XT5t`YJieYTVP28RYa?X<)GQnKrwN{lakdsn>3(QkG0EW;Rg?Jm9TWTdi{ z#V^YNcSa(wi5hA&jNCE44rlhUT|b; zy>xI3*R;>qW&IXsTM}WroxgL1V6nlndXyr}%Tn}#1(MdF<~CHp~DL)lueCTm35ciJB&QElK_Mk@ZRFLR}0oRtaO-jWoR<&&#{8!pm+Gafi z#pzboti-FkW)tVM5sB;|aLe}*qI8%^$P#`o71e4X-QZ-*#&WB1RMre_e zXpK5Igg<@a|Xd{u|VpE=J;E+dRrvxsevK>oBwXJ17HT8qajK!b~i zYAc!D=s)KX=jA@{vuvC7mFpG?`Y8TXfKwf(_fG_DXKv5tTdivy9Qhy{-+#Ny{LW~e z>1PbT*g<{&eHyrt;hhgli!E=ibgy)9m}ASGGlEU=ZDh1cYmfTK{C7BFJO&c?pL7I( z>;I%99zV3>pKM@>Vux-TY<3}=R^WJUK!5tEUvR4BVDl^NNq~P0_#?(L7y@ULz(A!c zYygh$ick#R7}nQ3j_)cu%YWOx)l(f2IN?lU%)|(QOZ#uo+(Ffe}%CtSefg$i*tju#^dJsv5D{3+W?z+L5oh3V4a!~LQD z5I@@%+)<|jxHA@s-okw>8gP%a-_3eB32-Q1E-Wf4w^-o38|T!82QO{;++I5CW1PbL zZn%4X`*y~)<`(_{O}OyZ2CTrV3{XKr*pF70!i?ZNR_w3)p!B28dAP~I)>)ECpq7wN zD29ICgDWE;n8kZKpHP=Q&hr(q>c!io(j$ZF(Uq zOSHuG8I$65qg>W>!S+eBpu5~=FK4Q+frIjPS7R*q$wETTukCN~!h9B)N?BuGHUdI-#cP~pRCF~~ zTe`^KPRJiD}u+}G|5gA?foo@WGmeaS~dI!el zPp|nu;aqBe_@#G3w4rFc{X}y-zSK&&Bvr`%I#rcJsN|jZU~?_jA^=vvc9Az&;N)Ch zmH?@<+9N9Ld-L@-V%w98zch9-xmPibQ7+HiV_5Gbk*6>Ko=G+?9X(w9$~CWaMLLZ& zIa(XFr9PoDFUsp(*xfz-l7f~eC2YK@hNq|0r6-jj=&gF@$+64e@`q2@Gbrf2+<>S@)wb8I#g#L1b4VoU%VH+OAsq#XmWD z`^GgRbea@@n$(G+{C#U7lF4e(wAHBH_dXk|v-s9B8v9oF%D@8C^|mJTrg#}%GLaVF zE>LdbXn<-n9U=8ocfvv`!h?KShn|h>f`>PWJGzG_(c=+=CX; z2O=;21o~eQ!`8+2lG-`VDi4wjU0UDJkFpv`855M;x+$7NqHT9pxm#<{jNTqSA!l<_ z5bZzqH|s6C#lAldCOYf0#=;forg<|+w&F89w_?xJ>VHh#209p(XN;76`uh8fR-~@L zuf?N&f6}mA1Oo>>#HQ=iAvR0pOnQzJUub>m^X%g>3VcvSV;CkcG4!vB>-uN4J?;OU z{UrYB`tg60K*tcW4L-gfrRH);K`{IB+D`U+;TQq!d*S3wolPKqIyaE;u^TuU@a}Oo zrrV(dYY&hKFiLlws4~M)K>h%h4op_NIumQfnVg!QNCl?~%j}qh9!Itt{fOS<`gD7S z{Wx^*x`)#r^}U-t(Mo3rxC+oSzDFmqPl7B_bPjQiK3K*W)>s2m2KKG)jwt}mG+i2H z74+`ypZoJ4XIG;EOM1h=?W(97$ir&D>@r22)Kb9x=)>G+UiiFr`?V(Fqlc09D*^IL z;BUbRV!L+;ELiZ80p+vru=XRuc9T9pLLN;F@sN;#NA(7%jXT)*D$%(5`?q0GOf(uU zaau%D@vvfiODGbp^9+j+7@{L?Cf17tNN*>3cL-y_xcEC5oFd#mRscQ@Ke4Ei1s$1| z%jg5RCFr`m&A4R@>FM5yBe*4qpX1`;G%)N@pW`o6Nc6T@KEzr=oN@jQeds5+?+Doo z$BYDe8a$zgj8cNuT-NF0+Tiy>r|cORdyn6rE( zZF}+PNctqj2gU92VSK}Ms7*QAGH~g&T`ag?M8sQllZj*NHhF+Lg=fauFg>}>LP+6o z?Wa&is%Y8Y1#Sz!e}h{r*C(YxHB>LH44|0$9e zEc?t^fMCiq%lpR;q>6(}C*sXSf{ry8sL#0JU8VaYGzcg zMidym(%0ZuSK}~L6V~K`6o1Bnee*R`&69j%0rlRldN)^0+|=5NWRy{F2Oe|vr1$tmU$+KIiX zk_kL8!Wog_`v^rEoq#)A53`XsH)~6W;~lKnEqFs`@)8FWj}4sjpxJv$wAA}IJL5Ek&PUy>&ILfRRQ z@d%+J-*^j-!C5av!7%_0nxWU206O-iq)=ZffdmE>*5E6!51L2fe(KaC+T~>%hO2k{ z`1kIq4^qc;RPW;^VEF?F0BRC%=*d-xXQgQA=^g+^jam19A@?~rZg74B1*TW85SnyW z8^G4BXQ8-{exiw4#SnA;_nQGrpWjGOY)%53;HI~rl^lV)yS|4@h`r&0Q{Xqa?1Dkl z%DZs7tSwM=`HgbNzz zt4mTvMO!lq7kK;1OQvuWCE~y1M)*!6$N1qti-}A+bzNb(-Il=`O6e*uq2=!i5Ga$!NLwtjamwy|6;x0x!jal{$2j+&aNC7R|zhfoRrvYV}tNX@!|hxwY- ziKddjl)tAG)Kkg7BeN;mYuMHEEwGjZ>ps^vGj0JS1v7XVgvCdA*=3pKg%lOA4|%o$ zqU0OxssvAU*b9sq$Fy@60UUm`ItSh45?tVtLU%MTLlrW=m^P8%tO>6qmi5_xlyG4D zH@;5m@p{ZvBd3kd#~lJ?p2_Jh{Lmf*yW?z`dWchAN_t1o_FR4WD&Kdskj#fAZ~hq$ z?SqbPprOB?*L~k<=XWNzhtJVFs2=5=XZxep52+5cMvFylnm2AA&j`JpM~cn{rlNPN z6G?X3);;YG$6MzonlPmL8_2J#-8#Qcf_-bfk_;ug`ZAl^1M3#a3(gxj-KTba5pq|{ zOqdL3cT3r@hzQ}y{U310vk0chp>Z#ebtt$GpthNB@$;#paSuBUS|63N1(6ZAx&Xx4ztAtW7l6Ci^l}hW$(=9Wp*^u08eN z-`u1(Sbq^4UMeK^NxdUfNhds@k;U~|6SC>WTQ<)cXS%EQq-BL(n~EYG>o$?vfM#8V z7L1&g(7E&YZxf@0XfM&;s+fabU5DQ4-SUh-stXD6J=A6!)~`03Ql=WlRJU!UoK9&Y z6(;gF-Au1fnz>v*RAywNnzku3#5@cz*pC}V;eJ2+G9yK>vR1t?y-A!G;|J)C+MVo= z_z?X;e^(4s-7J*%jJJqS44S9s|89G^%BAzklK~HA4ODhZv9|zyMd8!$uBIQyjGV(q zqzUDvc*zeekT@^JaLBrJRwIj_^KrJ=6eV-*Ta-$(oEx;r^Vk)9XDiO+@q4^TPS{8q z>jdVbqDIMnl>bsK7q6{8h5T7yW*FqV__@M&`qcQjYLg(8`Yk`^y}WH4tTyMrloAuL z=;bL;vz2f98R2sLjH-e%BdqXYrD|u&yj07Q4XI!$o$xw>MUP7Ljd;GSgU<0nqgm6F zpm@!oIH@3Y9I09ysW@0ruF#3;04w=x7K|!JCC|DNT{5$n_vN0hm4;@_wSrFU3=I@J zK4taZNHn6wvM#70unH@T?wq;#Rv41NWv-mUZHeYPL9w$?a=wmFCF*z*MNTHCu_xpe zyA|=-GU~26qQqF^2WQR=^c0C^%u;tbLJ~I(8z?H4^4x0fFa1@W_3Ucy&(#l>cvTW3 zCP`97j@Bj(|88$wt%Az*1WyuPDWH9Z&|a2-bmZO)*@gj~SP~14)%~t#8|zrVQflrc zdSvCG56M_>Uo2aao`TmdP6zBaI#=ncAli;uHa~vQJ1R@JWq!pHGsW@2_y5}f=U^1D*`X*9L`nug(8q9c?p`8i9NZy`m4fzFFJd=eIxAo6%qRw8-g$(6`@O zkICgs{DCcY3JL#!IhPOMWH_!fVgq+?sD{t|#LW`Bz{bV6_t@@*E57|Zr zSEjVO{wiSY!wChu%$cGY(GrsK>rgtKYvAJVv(SSBU!9AQKjk77zw>ElD#sdd4Ce&{ zN~R5d=uvMRPM-H%?6!ReyStuv7>f0kPgf78d9IVWF8%)kfbFcq`p8B@TKfm9m=NT# ze?^R=DI7HbWbPoBvFZhz0KWs=;4}%qV3WVt*f~%q&=A`)?c=ZLx^CBO>TJBrK3=xw zs^{H{0?QE8c6bTcTHKxp zR=a*Nau}SQZIXFtzPfM^G@XP7h?-FCo9_3`*JuHxrWc*dac?n>NZ|a&;1VFXy3ac8 zS`>62iA7S&Z}Om?#or`6 z7L7J2QBL*U_<8|m-bDIH2=`Hu{1v)8PUl54-$)mS9MK5~uw(kT?&g0yY%B8&r$xqm zGvGd?`d90Jme=S0ceZIRn|$MCv(rw*uPo8>+CJso)9Q)op!4B1UBc5}zaH(btyO)9 zRMy!Q!}@5DoQ%Rb!7@sxLG`RoQ2o+QMCT_S|D#D9G{4vE(SeD0TCCzr9@Svc#Qu`>YiAmBzOS{aqv`qx|<7i*!^8Dc|VRJSus{ zbWQE*C$=H+j8tLKCAb|5%N!#1AT^DlFDyyngQV(%WHp0pHS*7nF;J^jr(VlPGN@+o z%=}!m*`>PBrJ?wEu($>_Xd&=>qI4=mqcXBs8e7-E10SxMtn!BMm1lnGy_%8VTtbv| zp737yu8FZcr+eS&DGKVha}@4fx)}=fuTqW{+Z?}BrbGEu*jjtsd)oaOhDs%Mmjh9QjT^JI^fyXnM+8>eC1mgj=0nt%Qx zqV^QF`W2qIABHERxtp2^(H?1S-aIZ4d`tvi`R>MmYWDE^CfxXL6jOQ_m^2Le+LoNl ziLL2fSiHapn}Sd#w%AErrSVcB8H-LEfG{obvNpafjf+$gyFX~KyVDdyE7CVB)41N4 z(?JkXgn7_pgfpkjm9i#R%d@7t!w+V@gda>B5;{&rT{uoRXX#c<9qx}eQ)}Dot`If* zp+4B#%;lDC-XS&&&p1vpjciPRYi=yIu7v%^M0vZKU`2O%nYJOY*2nZ;28g3CwEyEc zOEXy#zo~behb(3&kn7vgeKxME=TsG`Y1|Jn$uM`{>`z;7RdsT&^P@6MKNi&T>Ug|N z%mo5;@xtkjh>JU2v+=UKzex~$Wgxng00_fr>4_eLkFfTDP}9I*KB{R0_^Xa*Ro{Hs zE(E)YFkM6DsvGI?Ar{}wb8rA%ERP8}vKhRAz1AQ??mi{53r)5&r@uI|0#1~36xF_ylnmmg5iEfsuX>tf(#J=xf(OU0;D&Bs z!N0wvT{T5a0%gq#Lf7fPd&6aZJ;UB`R;HE^S@3YK_dA=?-WT#e1+HP!Vf~Zx#dY)7 zoPX6ah@Xdi`f-lvQS5OI6hQ%qgPGa~YDsWR)Aa{M?U79M{DQ`@az z7n#`iduB7hhwwu?>E0QillXk~(9u4p-&ap+*n*e_6pxcz10=ycN&tO31wC*J(c;=#FP2kqJ8RGRCy)r|sH? z<3Kt&`x#UBBLxhKjBkDkAkxY)AfMOq3a#sTk%e)+x{s38ngAr6e9h$hWSHD6&Gf8# zncUBRaR((GDv}2=7gZkWL^beocYV z&bTb!E}48B*PDLQ-_<;y>h_wy!p!X_R-2yhY^F@equ!7=3C|n2NM`g*=*T_zm*3}< zx|C$UW3V!|{8hjhh9HuNEiE<6Ppzu`!tN0HZwTF@x z5e*xfdJQgL8j_RzX6`Pm(_r`li~dQ|`_1aRo=fHW2i}UxzB@17Aw+{ShjC?p%Kbuo zPA}s}?S9je*p2jx)Z5*F&jN2UwWFChlPLeduNrB&AtiZ%$p=?QOo=o!s@@+}4onPt zP!TSPa`x@pykR{A@-G>~u3f^s!@_XEWcX8LVF~3u#&5oBu|3rut|PnfAv=~KJGUY` z)gG4d?Z53Trt+&n6aOST{knGceprT=-MH!>M{AX~qnLWqN4PHNW^*(wuh2oB!F80< z8|vA+#zcD5M@HPU?zz6UJv8X|#y&{md0?9^p;%>oZ}`wuJimpD%f;F{)U4NA(B>c0 ze=I927@eES&x|@U^EQRnFvV*UfqAbE3xGJpP3yn^B0b zLYV7N>CYxa^*^ax^lDrY#A`+Agc`m2Z$H5Qs#^OWtk`NW=48SyhC4x1PKIH`YXEW` zKdsSb>Ns3m0M~P-)n$THCj)CBQwI*B006;T#*xLMXMlvWRp`KhsQ{-AP6MfGE>P64 zJ6TUnxQk92a24*^0bPD>HT@ThKqrT`gZ3!s&GNT5CIruM|H&h^L0n)yB#M{TgSq!gr1~CE5~_Lt!*uY>V12r<)5Au{LrcKLAzKVc4-3!vuwJwi zZ!|Dk6#U&8%0M4;1@;2cZ-a{a8msHNQ)5}Vh>n6d;OqyKobPn4GSeGo3D;EV#(E8S z1mOI=vQ&7|x)S7vz>`riJAg`o_+YIuvw|4YbDXoeFTubrCyPkI%cz8As}5#FCfq5r~%R&csl*O*OFFCLQ9NG5J0B6&1T~i)@iyg z###Of^4GAC$Ykl3x-uZV16dYnAf&9F!U|s=u9nN7f=s|pc+#mMGgm3x8Djjoyz1Sr z#Bvpw`p)L(UblLCyrWQ#-d;IY5cb?d{8Gvq?@3W_cDqFog*jWU@nuln$9;H2JK<#c zeqBXs%1QMLDu3s146dYV=2u|NK`jkT zeWdJWqQZufknx&OW!-A(C+o)xVMQ+e*bG|rm-Q!P`CGF^{` zOyqQPM=ELa3A^YCl>5A+(>9<~C%>4}sj7Hv^}DBZ+Fsx(=WOl%=ld8lqpTHav(83$ zN@ARFG`JLfJ&1E4_i>#jh(@+a0*Ppd z2B&Caihgr?{?K2_3%%M(MXETyzrS;kYVjkW+tON)-MMm@%HmyZxe1Lzc+0o8T$EYO z_|vvsk+s$xOZj=M*LvG-yIv31P@D}9`gxnJhn$geG-9lUMFQd_oBRQKoDR2jMmi^7 zGmXzx#U@Ol8?+G2dqy|4YVWxlIK9|xj*{L_Z-1xnxHsN#!8wt7l@YM6<dpIKKX`$nVdG922?~fEaj(;dC=S&8icQ8V$sW z7!3rkxke|FA9V+Ei87H0V)X+(0RC{Md>{w0Zyqrhjso{D?QStLFYs5ad0>X%?nt!? z$jh{;Pwa7&c_ctNitweDQ(dG3oD1;O538Xn4n&SsZ5?i1y)Z#uh3f~GAYL;?!l?la zn>~NW6~?}O`-V?A;Z%=dl}>KqA0^lkINM1c@HD`y(@v^KD!~Vn>kFb-c7R#DsK7M# z6`fesO#eV-#54OiOJqb4H-K@QdPct&D*<$1ng}+*PF33wzYTdX>5C$xa~*&ML{PGd zcRY6moW3&#kYy9=1T7&TcKCwkMmommIpbj>_hbb(cPzVXjBLt<=~!ardQ2!@LA;Rn zXe^;&)-l1Hc01fZ89XlonZ~k~`7>GY=qBFtTN}{+v`6e(Ex769eMW1iXl}fEk{G^0 zp5OfPV7h8%!`K9hY)CFs=(=ijwleA^lSRK34N`%)&Xu0d2E5?BP9v77O3aYu!*)*2 zrt{Hs>7wmMp|WKT?Q_XA$urtdcH(w6)p$5Eag{RHU!Ro)E!SpJ-kRFB$wj^N?rSYVS+I6!XjceX#8aEJOy3~H&ZmLu=u%q22EylMJ4}J zd#+0Fe+u6Q&b!F#AGSPy}MjmDWyL@(l*?E$!UIaDA^|-_g=F`bBfSiGv0zM zPg)?`_`DH!qSk6n^BFG{XC@}uo$zggFM+irVW3!#eTe$ecGd6ykFK{2i?VOqcV|FC zkT3uRhCxwL>6WgWkPfM#L2_sqV8{U#R8o;F7! zZQEKO_{ujqB(X-PX7_ql=tKr!~CzusxDE**u>WXbmR`5)_4M(7-vGz+av>En$(3 zWvC94jy)%6ZkRO>oc}e+sUzzh^IUS~fw!6v4d?TCOrfKn4Csi3)6mgvifvpb-S+tH zGnu@8zb#$+Aib|%27EF*`oWXsrYj9@Q@hb5nSdj=Drox)Vu|LB`mRdU?oTQzWp75p zTM}I*Y5A_15bC`LUq6R`Ee{GaxqeNM>g4tZavLf#Td!t?4VHJmSopWzlzIhH?KXiz zkSDQ8t{8lkWI?=Sxm>96+;)D8irOyZUQ$uf1HXEcggk?jzzwQ{ah@US1N%E`THT|N zB%+5ZX=JV!RI6tqJ+Yn7c0*}A@S#SaocdQUL|XjQZ(>y_Q#si(m*U zu)K7jIFJpT%dII*+(QM}=IWxKT(Panw9+?RM|Bkn3C_ zg+$%jb{E{IH`f3^G*iIkZ*(2?SE7$}S>*p%vX`NiQivT}!?{fp#mgOa;6%B+^?)|p zn>~}mdoSbP#Ok}N2J5*QhYraF((F#KKMGtSNAiP|)suTyHIL7TQ}bR2H9zTMrf8MT zZ?h2V@mSPv&yT3b{PBH zx2#D)nCqM1QjirZ7w@%R!5)%W^B`EsJ@hgY!7W?iEAU7ciXRzr^IXVxcwLUz|@#wg6S zkL4_~_4>QKU|d(2*QWU)r?-Y>`E6pH*1n1r-M$rMGHT40j&x~qdQ%s74W%pt*SIoU zkCZyihwNMR?T4j{IpM8uU=(G|?h()CuR_kW9>__|37NTu`58lPVpdU-J)j-cguy+4 zM9~DYsDPL$^L9UD%29%!{Tzc)I&r*d_k-U?8gggkqy$*#`&wA0oPUuK3wQzKw~C@{ zfoSP+!$6#O(%ip+3Ab5?xVRg{mPT1IAVCUbyI#%0h>IbC)~DVQl9zUHtk@R_;NgBb zm!-?YXe7=2lIM;gPfC^GT`iNcmVokXwTG294OXv2d$z0^a=o(4!z**Yv=`bqb~jDp zJ^=(?AFwQWl%V%iS4Z3eYls}5oa7#&j++$S_$4267ea3uiMl&=KZY?vB&;XW}QJXZg-*X?6NjpH4~dLv|bXCmk|J%%NxRe5LlY>(H$#)3|x` zmT8~L7U2x*{WG{}ogj&|?nT3zJ(E8|V6LLX4~R01OFtElDb}zT>`6>^x+oOgliv`A zeiDJzheY9ACX2@b?c3A`dmbm#;<`ez4M)>lJFbb;0Mqem|JEkPv>4lpGNbYdy-WIX z0VLOi^Lr=1sR&KRQ}kSe1&b(pJPA$266$zhO`eTYo9GSLSmA*>&XI^W$5(~aCsocm zU3SbAAy|%J7fEi$xzco-O9h`+x*M-6=vmj2AI%5IHTs+XHC9!jrC^An zdrJSbo29RZK_k8FWGxjDtt^Q9z$-ljl{}jtEE7DMBv#Zh>`4|#;aU~FfI4|SYP$g)=*0rU+e(d|QT>GG=4XQ+ zP5wgA&xZ638|t$?EDZ%lwNMg~Hb5RDz?-UZceh!8cmF3hhI9@Y+psJ%!a1Rve6!w6 z6gUV{uOm? znQPgU9W4=&ovpyiP8XoXDu!bVW10%=qP9(I)S>3V^_gbDl`_M~NSX0naB$0sbui}S zesKAgd~gdfB-jTiy=ZZXWLw9VpC!%ZZ<)gp2Z=`i9b%knGJ!i3TL-_IWn3z=n)d!e z1Loqdnt@xUY)Io$TTyw-6!3Z0d0md;|Ft;t?37v{QMk7Y3ZU&%L;-$i?*%F#^VOCu zJ9MoZs5-b89|n^5A9xOu1JReagV;dy8{j{nN3lvw4kKV>6{b^xmYwX)Zz{*mw|8{N zH@`JegAF|mSq+`XilpUkY~?Urh&$ARCs1y3&+!!Rz@sSd{nu;_J9@FFC^>dUry^-Q z$wQJK?}hL2 zp7PCxE}Qb5ZOlE=cq%T%>_pNXfAR$YPAaHoGFAcbWrvL6kBy|+IYOtB{0W}A&L ztNCHZC0n=kEQ!wmdz~A6$O1>%Jq)g{bW9ev*%@Y9c^awpIfsv1IxKzDp+`TWwZnhS zoA>+yl%LQcw=ZujiGl{Eono%X+l3U9s$SC*lp#<9HXF$~^*NC_9uy>d;Ju6by$X=j z>WoyTC)uV55UW@WXX)RWZU10@mO#BnFt>fPz$9Bxw%Tgypv=3baZzpo2{2$P1LShu zNONY1vZzi6gwr`-L-5s2j{cG*Q6{uhe)Dv0gn=mCwa;lAU0 z=2G7B94nr7igqiVN-R#k{HfL3m~ju26&>YA99^nfU5>g1#!8R4H%aUg&+TYZThxm4 zgR1g1vU6SXD-?o^6CVohOZ0JZYBnBcBifZfKE^8sHne>#*zjIHuwaCcB6EMtBR(Sdi{1D*C{>0&nsYGMHA;yIB1TAJgJVwa zme1tSz@y8j-9+<|zucOXntjva<_r`35|H=nDn@o=xOhoh6Jf1|>O@?<)5-^}TJb(; zDk2@rNZouuIO*vk#3|Rp($cV);Kq|T2QExS1kK&a`_^y6pQM)tR@I(uYWD8Dw~Ro_Hv-qgF#?&{b*?X2t9u1^KHRzUKDDXP zyj{{MONqSjj%Uo%&C+MjOq|Wq zxl$MCqFw$R+?cB)~1Jo=FFk z!zrA1>0SPiyr=qhpHf3|32a=Y4wO!$Li}ut18@)Jr5wATz0rJ1n`FCbnG+vQr zjb#SP*skGUC>hXG&~;=!GS)7Gbeb|eO!8TLl+Zd#w;}HLgAL zjr5A~8L%+pLfs?8$b(jyBKfs`d=>YQ zlYD^p5{0ZD-TY3%A9;qpeNIyRmNq)3F_-3tIx|uB!HS^rY1asikq!Q&xBXllULD!? z8K8&BDQG_p!bl<4ZNdy#Y;8jBGOe!u9el4xjd?Xt#rzP@<8X~+w`z@aPGGf<1r*QD zOdCX+4Wwp+^PO0#$R}+y`snDR0tu`gU94b+FdtgbtBWa$&(>OwER#R*{A{PTan;Hw zeTN;L2!{^w4RO$2N9A@}N`m+fvz-Z_gXIW$U{;V1xNw+!usct4q~&!B#il2Pg2d`I zy;z}R)+f{&`R+KT=kF@YftM@iNHlded9k;Z`0r~?9&&6=Ik#6>J0i_OFAka(BUpgH zN<$vl^Q+L;NZHh3mr4?Pvl1>q=u)<7o~Pf*iKz3{tE4d>f@AlZUS;GUOm{j)yY1GnW9W5CZVlIz)l3YAh zyRk8q=3Mdt0Y@uy_G2q-%I!JuyDe$V)w~$RMfvd{1{&pE9Bh!h=iNl2(4cq8eFnYP zb^Tuzw6HGnD-T`0Eau|h`W?J9Q7mbBkuF%$^wzI)s!6#Y@vvV!;5D=GmH`K1H0#9b z;p3OW6JB#c7-ykppH&!M5U}%!!`g{juD_$3X{NDFwuy$m zXwj%fc^1)m7kT^!O*+etNO_nVx4UfUJs;f&F6}Q4$lXwNTd|if5D|ld7uU3hPis8Zo zNsL>+FWMNZY2NEDxFYK4dB$A(zF*n2b=a*(q)ZcPUyDHarpPMu6t;H3M(i%>Q{hp= zcIy&*D%+x^X0``%Vq<0WuSxOl-c|0mmbu3dZf<2$OvsHUA*i`M-wCsr%paC*ZK zwI>U|@Y#3Vw6)kmzHZ8@P~1^h)>&DlrqAEsgjG&-5r6G*x~1|d@}L1MM|ZH z>hKj$A2mc!f=#viLQRA8>{g+MS_Q{bfCehvQPr3uH9_`yPqbCdP{goaH??}-&}_T0 z^I~l%D&#F~VPZ%@{)RW=V0(K!2djb!odQc^mtP0?EK1`q+FW5*b66N6139%?Ifg&s z!i0SFLbv)BB()alZ|%4ltq%G+bs_9|DlE|mvGVc46C$=2(d;X-GqkN#zkyQ<#MC>* zZM(K=(qVSSUT>Km4DGh!rx3LjX-C^8Trha5-?&}M(NXe$PL;y{Q&MoWlz274zq6=) zY^lA|y0bth9oT%mssl{^9~Hx2s2EUKaGrH-LOGkP31r90|2mVl#rxVZi7H^zGy!o$ z$00%Ipc;@q;5(q`pgAUW1gC&XP_Qq15rI$msZ=AoSdTzb9Sl`5LK`UE&s`)mWr8TE z)rY!umSB{a9F*emZ?z}}hz|YH2=sh`0;dq$aT`N-?v;JxH0QR2epa>kQU_Ih-E&*o zG6`<-u=gN|1y+YH0Z!Coc1C{6jN;xPD+Hn8=oT3hKSjg$2XVe((I^fAh1Ig$Qwmn_ zuP@%$s?{D2kxB4dMgv_VC$SJ}yA;0ii@SMCZP5nMik>g1A}Whg9|#@IG^h;(+6YfV8MsE!Z+#Ld1 zc>YZmcZ#1l=trVa-{?5ua`V{JoK-xBPupV1=qK-n0^*%`U}+H9ocJ)nd+NE^sH|Du)kymGzdo+c}cUV)*3C}3(5DpzxxRA{z& zWwx^B#Gs$o(-rwSmJX(4)UVO^3rhNCBcL#^u> z^HT$ZK|_NNMw;m&1~!OseFhr4DCXYPa)!)AjsBi@!?xWRgD68+o!9^uRgToBEPo!b zun2E4|C(5i`El@VQL*W&lLB+}k;&(bW6*gI4IMe0mMx}X*%`ti>K)CCrm}mJ;Oo0U zm2|CMuUMtg1OWkS@qNo!2`hY5W>lQ#ogk5f)}8KQa28<6bNU6tVqA3sr(p<0x!$Nv zN5<27n*=A@yrgn5gpseKwMsKV3{hHu41+P&m!hflH+k?4BP|~46Q#i~A_;z?PA__& zA?ncj$-{OpRt=|p)rkRU<2D0RvH3y+bT76vxS%PCTPzssq-$En=vS9|O29X%y0RD+ z!->x5*;d6e-?to}A+98N*4Ehq(N3s5i3id-$ufsd$=mI4xz<^EB^%P+Yu|SN zv7rKvjvlKF>{UutxnXi97nh&NgC4s++&~-qnZ$A0qk)GHO1eD|r@*^`9v~n2!_=n| zfD7kie)06C`n1qN_*V?_>*#Jkg7R-%>7WDt4~4=m1!=OiMOS7j#gI4jSqtsnw_vBY zbcJ`M;y+zkDYv~=j_X7sV+q1T8HPKvpBwj zV7|j&2WqMxSAVO82$rnkq>GXb+j849FE(b6@3l4%mI7M#?$6?CR7}%-;ho+4@2xdlBZa1tF5K6N3#p#Wqjd#=!d~rPkAD?% zmurbauR4Ub&&%qr9Cb%z+p>@a9;B7a0sj_ab^h7fvPyZTRu*NBQD>u%3!<=*V2_bn zfCj$3=n^_)INB879!?EhZMC(O=t!05gPfFucNl}K#Z>bs&eGb7wUIp^2SZkR0>5S| z&}}!4@GZpu)y-_o;U$tM1&}dh8NQy&F z2ZJ*39agdtKR_Ex>>GMBpf#{IW^C@DOpa(1EsYv~VP395{I=i;B*e77;P$((L!dHw z39nZ*Gio1Sy%~tj8e1RUlMp{gLIB7y$Hn|LP{fuK?YyG9GQt2CFxp!YzB^dP$g!ZL zX*W>YtHpfJNJPYCu;X8)6hoQeGo=0xjKQzilFw;6yrPARn{S-p$B3gTg;zK=_Xc76 z*+8!MA4;dJM;$ax_F7&ti$N=IQZq$0HX(i%wCj1QRalv*%!;@AJkL>Ko39Ln2FVBR z1iWl^Z?zQLYEVq~n<)63OU^k(G38(2612xK*jw2wm^6 z#ADv5(3_mPs-6UYL6PKdzjx2c-LxW!poJCYF;JhT!eZ;nygd_=cw8sE_5``j>rEiN zhR%QqDGio3ZX;?&{AA~B*=FIYE>>C)95eNXaPr##R^!r$Z%!)3=BY=)BrsKt=9*}8 z=N+@WiWP#=wzI)1)t*Y%XSl0nsZwF35}L=^*|b>6bz*RYIDRfa>GrA&=O%nwDR99J z6a@^J+b`{i9=H$JXa-^y>s0pNGqrkkId2@0F+`uBA7%3C7!8T#dt^KFY*0Ec9&xT5 z+Ak9;i|65laibw!ZG2F-{s-&S)wtry`2vejg$lWW^XlTBQ88-5IjJ20OYS?|p-dNT zF+rZ~QSB$*+2op}tOr{ff2^{+=~o|4+Dhf$q8w>*WbUVJT=5#*NOw(m=ytU{e^BJ? zE_BVH+l-@?(8g)cvj+-l%ezUl-?#}y&E>HjK=_vgZ#`eo{WBH+;LOXbJzjTy@A`qv zy5T||FU!}ua~;D*3X0{~lP^tTK?+%bzzS;WpX?TTq~&^*Dv4c`CeV$3qiH&cKs2r6 zMexULdy!`u_UKACz3FDg;tT1$@es{gd|&XYq$%e2tSjtb+ZP>T6v@-P6->mQG?|Vc z*7hC@__YO!8pi}XRMsV74qG$!c(2U=JvaW}!U-f?m6UMdzmiEOb5VFga}vq45Jt-Q zpGueC|6A!2qBwswz*o|LE<<`pxSre4VM1_ky3AZ1?{I&PC5#R96;R7if#%E_R^O4H zph!QHnt`Z??x`xs{D}zK&XCHcqNkYr3gjxmcfmR+X*u?eyGJ0t9&fTS@Wkas`_&On z??x1-)g1KdFVqzNbb&2?-SV)a37jTFafBUnMP&zfh^%!N zc{~^oN*elDI|#B|23rFG{If*M69(#h$Mh#vKy-{@!Wal+*mtm-34&q!gVNi@`C(qs z6x6^+E9lL>67mOVjAX(3`p>D**zx-dH_XEvL0z1g{@)Z7P#_xMQAWm6s;n)$2FadlYXtoP~Ax z&A{>cSyu$Q+2yI;%gow+!50SoQF>e{HB%p+r8YS?3c$Y_sl~$i#huZA-=$CwadoLN z5@=Q;T}@C{Jkq%eUfr(KX~m|UK6mW z#jb7_A&6Ua&Sw>pSmd-TzG}|S!&5C41zh8G zm?@0iMnlSSJBA@0}XK=XR1Je=E{qtCq6-~e%Lvc#^;eRw3M zz7($e%4c0Kub{`?SL*ey#2-3^OwY5OE~VTTM*-)*MCiHJGk2`(}uHVuKhy9X%_(qzcM z+q;d5RAk{F8crEDp*kIqmqSeTVLat_v*5h+j{s7C4!34=tDEDnrrtYNJwgPIhw@ul zXNI<$W;z5@wS3aMQhy3~*1Iptorp^o((Q}2%#--aj*89=k@ZXw?X|`_iUYINya2$W z)6{-qJ=?Z+f40e^)^~8e*nGl$?C=OZT9{=~$gtzAyV^`BTPh-yT|lU@#~UZk&CYF2 z6;8MsI1GEfA&PD*)F;kk^?K(UP4+5H%F8O62tdJnEZ1B~S!GL5#M~FZlbr|uMqU3` zrPFPy_z9I0KkSOwxERNoM=;pg0cOieS zfk=N;Cw~!!E4J^GY2;g;UaJuh!wh=&h;KKbME2R^1kI*iZ;JO+6%D0|0vFvi)=3Sv z9hSha{&Ww!&R|#=SIL>Q~?$ zE}K`Y_!9wK^^1xg3ri#Q^lz^sg1j_38^a?;$yPWzT0B?8D|tmr(~8{Cd!=oko_%fV zx%pt2`TfMp7%xK$vw~Nu;~HiMF3MORivtZMj+2`)%a4Uq*fMA=Zf3rH4SSO)Hr{<>>HfyV0^02n|x1C)FN>rV@!zeV0}O(YlMx%Pxdm` zckblH*4$aX?`E62se9Y3LJPt)#sy!J2(N>s)c3q2{rkL@_Wmq3sNXJ1TxRpw$IsET z?4-f8xc((iKLmyua_Jy*O>1|2&p2S2PdJ%K6{N;~cVU}xl{6|hbohA-OR~pEFVooN z(nj0gUac=?;V!y%&Wix;;gd>&J&R!J)2@wg_n3@pbuW+U_j9q{A0?7fWuEkE#`P(GJ6K)5$3K#c%S3^%l8( zA#-xrxQzV8v2)oF3$T$_A$hC4*H2^_hKmeClm~s=@;TtNYaJsFW9=KY5;F(Z2j!s( zS?dAD+U2M5Z0486+b&Hn{J2|Q`0>uz+pQiDF^kd=*kJ|PM!-=JqGgpFYjGhXV)-`& zYmU`1H{vs#NF>OTR2b(n7;zgATN0am=ScQ|z1C;Hv2MxApyZ0C-w>MK{}@G?cY#{* zxj1dM<8E*FwE6fevEQJkMs|1Jj`Z|@-J*a0)ekOYkP_&7z&AluSDf*y#+zUYKr2CU z?S8-Ui@h7ii^f*qdrv5g!OfS9NA|QotvLYD9QXu-+@m+;a_SgQo!Fqt{~5~aJFUA!Y7dk=*8lv z(|^mX$Rmy$v(Chcbv>zp#y4`QZ9&V=4THbjq{u$sxw>ed-urW`BH8ebWRNl?tbld9 zn%0LzbXaVU`ilZI`xbqy=Sce!ZL}S`?IW7!|G48K{(@RlEISyt{?KtLf^M&p+UTkT z&p4IPExgKvlqp-WRnZM~2MF*k+=G)CD;lvg1_&zq%}SCam5i~>sflu?dyvKzV)t>5QtLY%Vd8U(fX<3h%4*??nasy2Zf5*F1b54R<7olLeJf~99MYY><4c0?0xOd8fYSGG zXgJbrUJnqe&m5HZ&LuYO_LPYj+#6p13ItTs#{Si0NqVVq67|yr_;xg;EA{ipGVbxE zz_mCd0L`&PN$R3)8gtt4ShtfVu$>=jo}zKZZd#ae3eQowH4JDEcTxg%Lm)g#%< z@NNHNeLP|!506+SZCV*P!v^jEy@u(?M&J1|w4__@HWtWn8E}cY8m*RUZWuQW1ihJX zc3PF-5edDKRB2Jf0LQ`COA)wSx4*l*ShO&7PeffKpbeiSW=`(h+Yb#-ByhO*V7Tku z>iVfA$M7v0{ZYyAufOe_H;moTr%8O4&q!WjFh1rH{_5ix4>V!EN^RnD^H%E)47EUo z<+eZ*a0brKCOL2W)iK#6{UnkDKjBWRbc37n@lmG0%W{t#D~hhaxJ79TBrNjsN~WlQjP}roIUN+HV|}N6S=enmV_RYMOET!$OE7xsFhwFc zL^Uq7uON@~#X*1+^Pgss1)AbYvByT1FD&X+EVOlGwDsJKl!Gsx9yHnPM%= zVy3ho+vx?=UlSmC9`a{EZ^W}T=8=z9nvv3v4i1^n;}#3WjcgjdSXrmaRtoPr7vKig z)@g@;KIy#6Q=`*g5Df)ZBqZLm1Uo}9TFoYTagE+dsfX;yjJ(RXH&d% zrnR+aX2o#(u=rW?r)T8{&*lzmq*yYIu9}K8PU7HKX+QTjYXB-CHyv?xhFi0Wg{FljwSWR%bi z$$^+bH_JbRpmKLRZh_wJ0#j`0tsv-TrnnsWR|Oh>g_nk?@u^w|o`)m~;Kgo$&R!r7 zBJujDLVp7V>7Y^tgzc0O;001EaF+*JmrWm7pH|}m&AB{hg>eFq<;u>J;FM53%olhgzSE4Pc@o;kXUn0+x2Fu<*EWsi;#0V0c4^+=@iknZkcd>|!`lp? z63VGjH{vP$$tu9q>rnm(i|869k^V1PKrU8qVEXv~ojGJQf4B;*->QPSOCJ`SE&4}wEu-6-ML-~Ho2`0TYw z*TEk6*?0K8!zL%5t&en*9C1egvB_93YMOEc z7?JzWeJ`3q_9oiVE4@w8ZL*$8NZ>`dSAnSr8a)7v8L1;v!%wHyFp5P8XAc>gn;oxW6sTt(ztbhgn|&(2?CX<_?My#I&ZLlTqxq&6K7Cb`gqsd z%3>-r!RQ0w<@?7kKNP(DunGj<4SuE7h@06)l@@w2M|Zu9D-ymdcJS#nvxatYW~QFF z2+=;B_6|=6SHXsI=`)9(x{yakdSAx|(+*>OC=OBw57+auHYZ-kK}TleTFa&5q|40d zLe%`E_VeAEk2vtvNAj-o-t~3!ZAQ~T<3PIaoSQj(!ez$BuHa(@f@Q2N2#uGRFpEI4 zjA3mWlh82Nu(=TfI9kd4Ol|L`?@Jk6(x#MY}ooeQ1b3n)vFUpfLUqBXR zXk0)2R#Q2x8BmKFFJKYOkR)EA(4e%fLO0j-nu|JNp8D-p7n@vsU8=18Ka;LoFxw4! z1$=a;nGv@L3o`YDv_7N^=Q3A8BepX}Ft3L%RY=49_AGejF-950L+7avk%$YLbj02O z#ePp%-o`pHaeArtrjs=9KwUZ_l*WrZv;IM4bMa+ZIr+@f#-JAm%`uS^ zU)Y~~6WcNe^B8UE=_BGF%|ZB8p*FEV6FOQ;lr7dqw^(Kw`(|YthqP~-2UWURdX%|^ z%s)nl4gx)XD$Pk|jmEum!v!KcCg`Lr=i&1s(R9E4%5Y2IzVOcN?D5Wi-2dNm@b7=0 zgYKkzZAV+~#+_6lDhO_Y_H_w~uD}04TnX*te2Nk(bCg6?NubMymU5Buh?ZXt`ZN63 za6%x(@<+P96zU!nb@a#8j(c)%GvRN2l|aY&P^%`|8&>p=`zz)ML=?Q}8m77`x9sG!(~`>dR~-mOcAjHE9vZ z67_62!Ly>V6jqJ&J-Jc&CD1Ub7I8?PD-nVBnAX>vak3prs^_CiMk_!pu7O@Hw=B zP8Nc>Q$@0M=0{tAbb+#trUK8z)GtH7PNP5CN{Bzt z5#mUYkd?7p+5huKYwRbY+G1kL*}UkPNJjY$;w#seMG-&x_XIMSArs501{`)IX0PTz zdp(C{End&c^m4OQ0yUFpVbaTz-Otw|JJ>l!Iw z!P-pOBY23IVVCMcBCHzU^o!R-fO;>fTmX8mwfAv{|7feBv*M*`uNPL7$AB14i{&;h zKM|WLCZlF_x(sKWwb~8~*xD+LiCrPYDJ3(CVAp@Jn8x@3(YXS~4Pc-#ng_bp_BUVt zcx32iHdI2^(ShS-S<7wpe)~4u#n?e;u+UUf63w_~4Vj#A>S1n8uE1N7A~9Gr=Bqd? zU1AL9>|^O>v5ZZ}S`&R;=a5l}BBuRO82d6T=qPAx^T$#FYxnXy7o^HFZb#$^O|N^J!h$#k%shk!)f%5hTDZ&BTdq0X0^Z9 z#ZIIJfF25}eY-oGy{5$~lJcSEq$m~4Oz97#bD2e&$I+$CuM zqd*z{ZPHf7Q|U}^u$ z!WaON4Vh7PTA^YkS<4|cT6iGW6K1g1WrCCwBT-)HQLBoPy%?3n>fF3bu6j*0SN2bY zr-Y&D7zO#wFR#5CFeE!wqTlg!)S?S?I6umcUQau+@6WxdhJZ^ZuQ)U=R7>Xu-qs~L zVYiRZDvs+El#f!E6WNDAAlQQxE;Ac&R0HMG5A`#YiWPKkz>JjeZwggnM#zZPpUg|Z zh*B=P(W3)eMg2$3e1AneK33d1XjAr();l6|?Z&&`((LnKy-nTSNwH1I!^cRojMiT= zkK%++w8V?pnrf8GsRN$l{G@E-YF4{#%QyA$xtavFhR8Y0*ML8)!H~6|0i#($+ETXL zjSkTur5Q(S=9WMJWct$SnfGY$7sZ@7>zmcsX&$L%G}&H7M~_2h1^-b(!6&UGE(zTd zNBiQ^+t^d0SAe6jgNicx3mdZtQc*(eB`!6}zv$JjvxK;?BlHR8RdjV*Cm2w7`DfU(3$-5=d=9=Db5(D1> zmTjC%6#l{}T_QP+?qq})emxSyv-R?9*O%iQ?1&A$_Rg4^mFVbXq(Zboq-c&0*QkmO zgtogiEJ|?f@nB3FJl-RkUE$_AbzQv}E9)}1hL1x%Joco#brVOe?l~2$Nu4a|_Jc#s z)tyr5*af&V%tq8d8M~&K#>i90(pYk$jOER&BqW^_(hcBS1|d z1;k2`C0L6Y^y-hwG6I78sHojLI?u6#Qs1_yB#$Lukzh`0=CgivDAg?Er*ZL5_QB(o zznpzgT8_Emmdtlf9ObH^8eg}INu&kHPW5&V3diRY^g`X0dHv)wIS>b1e8sDBIPzbA zns#x&E9yDRGc&VK=_tknhq}XxPiY^H2R_N0<1jg3)mmR$%m?bb^!c7>$4#se>i8?K zI#A@ahrfdJRc84jfmDRfg2z8?Oyr-DQ|Pm_3HTN63}MwN-4r?{jUUDU&ByMC-3V9b z_PNcEWLy{^Xjg|et!y@&DQY&F$)f;pDV2#-S&y>qVL*!Nqdm&gEHnx&k z=$}RyP4mvyO`hk7Zn>H?SeT~uLwDa2WSI%|8y|XCVE~H#OwQuJRzjPVHpwhe*;|?Z zqYm!>)2P#8evJ|Zy8Hh+BPt#bZy5ticS36_^_C^4`?Wwy1c-O-`V&w%h#N&AM`QKQ z_9ofB+>^NH^xwf^W?(rvx}O)fs2_vq2SMf?oZ%)QA_!?bc@uq*K7S5C0BTm$<(pOh zq{3iK6)umBo|a2^;614xuxCE$;N!lma_Jc5uQ_#?3Q;;GeJvaU|D z>OnWT{t%a@fCJjT}?NmfC5V-B%luHLIzqNz;#9k+I-=P&CrSO#u?UrE{{ulD(e z3BSZDyMIk#m{IOsBMGG-FNh7^J67>%-@x{k8Z$0MzGYM@j4azYex zo_&mg1D+=Y@xW9;z(4kMbyKBhx37_NYeqk7wePz3FYiNEiEOSw##u;*YMOXnFyY2x zYHj2c%clDX?J;Q^i7w>HuOI=6&pAA&`FuY>({h}5sfTE-H991AQGNrh-j6(f(1^`g z<*mdRoUIg3Yz2GRz@9(9GkPO~=} zYxIVra|V`7&sAOKlvrlBsJNzsattMNpny`_&q3$3=oq6TJ;Su~Y z{D>IAGVdTd8N-+v5aS+0Oz`oqFsAGWwO%!`l*dz?r^~j_ zhRa#a=PE&*-BJ@Dhud&}5s`IuYm`U3PLvcJC^x@{q)cEMI+eezSWOU;x)}Fo9Zws# zFAB4cW*yH`+OwyU?tAgx^g4Ns!`B&W@tID-mERoh}d`Ld#XlulAP&DTDUE4cD_42kH zM2#M#e;Jy%>9`XRv+ph{u{m`7M~h<`jbK}0+&^#;4lW<|AN>3{;D_+ISWaRvm+*|6 z&o-;5gog8Rs)eSMNPcC|vUk97TIBu-PMf$`r@avtVd~?sB^8XZZgVTosuU+6F^@i_ zB}6&tZapx!tkrrR&xu?!xu4e%%-$%J}k?}WRLtFpVj2;~Py`yEJMo~hj=Fcdsdda9-?L%DlG z(N-F{bC%22v?>t1I5)W3yB+kWz2rzf=|LY?PoxrSHrF-eTTmtcPW~Uoa{#*hs^YKi z-HI6P>|%6sa;p8w4pw7jKOurFa-PQ_fNOy^yo@-tb0^3#D-p~io~ekkoVy8LeeQPp9BAi+0#2Sa3K&)M0wP)_?{ASCGd zK3PMKbTG-XF}0b&aFnMwSKMXQyG|SWZt^#;wov9Bf;bvV)%Nn+NJ3-*D`PlFx?|yA zmUB`BY?doVB)1}c1x{*Erq~`Pk5>WmAF`J!7eoNz+>)>^=oUv-wqG`x+Y&VA<#aN8 zKXRzJWL@j-u%W+Tts;F@Z66Kx`QAi7doONP?P?}Zy6JhtKRqE{{ItP0DUMZV*&YtI z*~aM-{5d4W(EP1m48-ZRqRItAijvz<~ zJgV>WBOam8cUNUE58faPjAoBOWDJjkw>vD%WiZ;wMVbNU*}PdZIqE>qhwwk~Fd)p5xw|l;Cyi9kgb68&yWZif^9WKmn!F|(6>YnZc1_MEe{<8#Og=IW>fqtQu zRNkux@I~`rbD02MC*I_vn?E1W^|myf2Hj!GUH1xMlUW)fy5K%L^y8ON!B5pI@`fAU zMxc~WwI0C}weG&KiAjDb!KR;$FY4INLuGt|~}?*H&qGrDqk`8!Ngv!Yhl^XBg7xR{C&k3naeqssB;6?OX4 zTPA@^w&@}wZR42v5`#`jte0ctV~ToM>Rs}+E&e0%+k<0UnPbLBRMUexI}$NB+;GS7 z9~WcN?wS=XZey9Z@%f9fXyz?5hmAORsk+{V!{1d1ntX#1b5#ZUFh0%}9nJu*hVey#~?NaJ|g zA7$s`nrl&?wi;+O8x&l6kk?fCmvPqIFJZgeqSEyD#9EU_R7IRHk?<;=r(IM`+khdn z;#mNaY{x%kaaVss&!M<32EUgmMz@-VPb1`hIzR3^k|#MBQ%Z0N zX0!6PMk}#(kgltrDcMxCpm)fAb*5=1#(ZiYWZ1x?dz+1snQGE%1 zAA;2zS+WpaE9s5Ttv0N90zXP`bDx2{Tc94)a}0PL!i>v$g18qH!ZY7Mb@IiI4FOqR zk~v6~j8JcMIjww)oG`nPKE?vQ(R7=`>Z4~qc0ckt4_9(#1rpdKi`7+%5P!Sxn?JA7 zW{TYwtWk70gyK?3M*}Vw?zcV{%A<~?BX+IlNi^>iXHEyd(0CfnQSql5M7p^ z`-nyw`&sphYF18{t{+JHcr39&@LoDXlJ-9SKkq{d2MDtgReLDF=wtO0L%R(q><=&S z4)~p^7EMKt&eI=aOzBMLdrjN;=J6S?1TVzi=9DK5Pi~TkKI{Mp0V3wO8#Kd#_qGN^FAI)ZTmZ^cYf72)w^iwJ<|uHc2wdKK9`iLmjs=saa8GjFh-1^KDooyjmvXT~^;LHH z<1zlH>T}WR`XI1S4#&OFH?L)$d>ScFpZqJw+11HUi^Y=q^o%Q1cI zwz@&QxWs3hmWC#2^jl2fHbkJU&ZB#xJF8PRmrtmg6>`kX|7gLq~tl8x*Z24!e&N zkPB$*!5@VdE1OWWb^-t3#>pa)mJc!n&L-ri8kBu^J@?c)j*d8yu9nYPz7IBIIaD zEy?a3KiqiP2IiThZh(hwui}RsvI0F($<*arS%&q z4Bk(E7~9bJqYbiexQrGRuTM$Zp2I&xK74=U$z4)PiU%-Oz*lNX1~34`RE}I313b|| zqG|Yo1bHBLfM7f%R#B3dk*4Kt-l7rNIDiN6AdO@#K$?1wB=U2tn|_VvK*v3!xEf<3AFHj zuSX#keP^N%z*`d_QIphX1M&Q#_L5W{>CXp4#ae4bkogYwLT*|oF(B8`1sXs{>YEqN zN@3CbYwcAa#9!)Mvc)JKQbx2ss4wpW^p|9+jA;WcX}Yf z8J*HoV~V4T{evJ9&_?`S(;xv99!yYqq%ea?Y1Ywx5j4aafr-S;PyllmY+ZdF<$T~1V}f?^?98wO_0GR+5v(dP-%Fk{mqf`SQtrp} z;h-@+<}~Q`l*}(H=hg|%VJiuJJeT!#*73R}=fpIqLfet#N*ash?Cd@{;^OkVNgr*; z2k&(7CnY1PY9|vJZtGWc#;P#+vwxGY=F|z9E0nzNO_DYMu64p@PTKHuO31SqlBBRl zMXIddRe7RRnRV@Fbe&zzGtEup%|G{y28O1ZqpNk8j%7}37t10)10(QmXr!5d+275V za(-wyRVCwon4b@%{)}s-AJ?;3!Ys#D|1lkGeB@*149u?Zd8T3@ona7&zL3rU2KqlH z@G>SSU?NgWbVY@;u6$)(2xHv}VU3e#BZo}!*Ln0W!8st0<-5wg;@TW1f zHyz^~={({sm4OqETh}_jDU=z9&-~_BB(WKDpChHcXVS4}9Ck!Ec;Q#2BUbvJO`#{j z`#~lg1}oQL3(7%N&HS#7N*~La5mr13gLlmH6j38oHf3V1XOx=1q|yv`A1D(88VEHC zojagnwKo2C-XAL{#mlwF#VX$mc>81*`#NYHO3Y^0xgA^Hh@a2TXX~u z_#~cqJR01>?lA0fH#dEV}}%Iq0~U$o-y2-Y<3a{fTAD& z1?nILQFr|UkwRDpA9{-+V~%bZxy79Kss5%x?{xAq{UL!}2E>7E?+)4o{p0zE4a4g~ z-)wvDO{ONS!f$y*d1TU9G8DaMlb%n%)fGGTg z{*thz6Y6AyzU%3K{aOg{?NepCI2l^|PD~=@Mvy?vBZahU<4?*q7iFD)@k>A7?bqfghO*kz_U^O{Z(}`}T;Z?()uZWk)YJ z9qH7?TAScej9Y^ukw5br&BNT&jliX(BG2s(rUsXl z2?H@-o92G{q?b-_R!JE!ha*8QpDvL7eOu!RGdW&!%1sVy@dlz!dR%m31-wDIt`~#i z^b)1IR5>5k&#J`|XG;}jt9LL%w&xXlC&jbH>tUW%@Lqo6&66FWJnu`3gK~@JlkJJ@ zYu%dlzrRedf_3sipKK~P8-q@FFlQ~b@99JfKg=Bl4+(wL7k#iFsgmF5nm9-GWA3LK zcf49!J@#8oflkb_IxAa|3L;PzmYU|(8t^?T`eRhq{jy2|{XPy&rjh=n?3_ssYu!kV zc6RoKVN5}BRZ*)ACQB!=-P{C!RFo|}CpJJQ=|SSmcMNJJG?8`~lR~js_a!HuCW*(| zX1;5#@lF`=n36>AebfHlcNiH8#XyR%E)*M^9jbO}u{<$koYmsSebmG_zKP4iH1Uv2MqX{YsP!MB3 zou*#Y2&bre=yBjLL)#_)7 zo|?Jk<6;E_42BsOw7=2<$Gu+>+ue}#)o+Jb*KWTuv#ZzDK9rhqxfbpFWn68S3ioNG zpsqWL?%DWMfzGKWEac=$OXekyustGc-o=@bbN zTnvC~l1{(C2i+M*0uOe?g@MAQ{dlv0M8K1*7J5d=AQ2l+PaWYmB|=8LFAj?O^C=ah zOdp8iL8at=6d?la7_!g&fLNqQZOEc9Q6*kKaHrG`CovKGy*mP1E<%L|1!C=SchN_j zHOYlwGJI1Yr0fRwcTmbE+a6JqpI~2qtXd$m1#p^vgJ^Xn){hB9@*4t=7 zR-WOG##gOP;|{PEj=)Oj7qiwjeY@Oz6<5s(U%oKzOZI#&43tcOFh000`(Q{GKo>F>_f}EUw zinSRy&65~^Pqj50AgtC@h zbh^KX@k(^~F1BQyL&Vj6%7A_{Ja86DKT$fBxTOnz z$hoc4tUje_KQ`n&Qa$_2R=0AfkuT_!UfJ+6D`VDNJ?8h{5>i&W1M2-A)dxz_+Hz)Q zuVUiBY9=aK<>=_R3w49<&4#LGSj5P|Inx0+g9z_v*tNjcTD?7aQp36rB4}6c+9w3# zgB4VDG%DC0DqyoPIVkh0oH5}BjlLr4ss!PRBsi>)C3oeE&8$jEhYi28tzq~Vgtb*; zYquhEv!rWP-+7;AlE#x52%j+%hB+}N7{&@MQsvPodE=eJV}9spXYiCplP5-*FX6j{ zwG03D9ToCU0)9GyW$F%I*KgTyinrrziB?J|%xG84DJyy@Sgu>_26BK!oqb1nQQ`Z%a55CLF1OD zf{@#bdQIyz-!Q^2<8TMlA2AE9eKhnFsIR{`_`hwh&3_6Dx2;-TSHyh}dh)MzU_NgO zyWU%N%ma()Cevd~Heoo7H1$N@g3pMLWk{!tfR&|bl1xyIwJGxOFozEV%lY$*oc7PB z3}49yxZ8{AIV-$wd`=|2_2r?-tauvj?o~PE^jSP5r@PWP=S3spoMAX)6FM}*U_TCm z9K&1t3^B=@P?f`DLzNK{LydM42%FpWYE1o!cs8Y%S_0foY5OX$03Kh`>2bKED`M#E zywX)@=VxcvWZ>4t=ku9P*x+uXkCO4zTCdRj4W7X9D>LdI0RV>wk)A`YYBIRA~o+E0#rwz zb+i#r$ms8=5(eYNE{GE)gT4bp04lYUcnxyRID4k{9@xE&b;s~3#MgKr6I2T{L8?gd zqs9f>N#ntS_!+oq<#^=pxh-*>dpoLA0<1v>N^-F8O;bBc^0IFYM&0;1YPADFe)?KR zL(j=SInH#{lb(GMH2RY~)J||MS+YGNo=(Uqs_ImfE0REs_Bj0kIa(kyk;GsTS#;Fv-wQfIF!y{L()98%Z z0c<9RJ40McLp8J!2d~9y!I}%$^<72=;RZxx*D>W16Z>JX`DQ=*@)&0WQ!i1-envsL zk|I*o)z%pIez)9WMNGh1a)3b`agDBh#*DC0o(nS%>weI z%XMe)C2qS4j-pNx^3r>L!chH+gVb)y0;EZY{UiylN!;XE@mS@gpZF!~S-m@wni5oL ze@ae2;riyXX25ceGHuq5e$w}iXZ3bDrI)UN&Bz68%C&DRf+oe}AU2yFP3%#)e2B@* z87?^(j;y2NUKDT+!FrfIb7aaQ=N*U_HFG>?Q)Oj2EzA&R|G-`B&?Y*M)3#}oV(je7 z{CE=umx}Y1!xUF=2!2bSmXdK4ce`_MM3EzWG(a5J{nE{{p<6 zkt-=R+p_zL%yebl#7!dW&wd!T?mCjhrp);I)3FN#Te08SC17cKZ?j$z*XiB5P(=gP zfzMcZUf=|BmECU2<1m{V9>GRcCZ-11%X&={{U8`tq-eiYYULu0S%%cg#X*N@CI~j{ zsAeMO$tP6$PE~5E2$%Hk`gB}vKcY0pd}z{yx!RvBSh&H7>ysH#C$5y!iY_HXrn|z5 zCq+YQ1B69W)FUAQ-{o0my&Vs=9k40K0Z};wS^ztrbSSQana(=i-GlAiF0DH z+ct?&+f&z#PS3c!^Vw|cUzgNX(Mimfu}64efmA<1_Reado}&3 zs+9zXP9_WTJzu%AGK0L$6`wa1NtE%h)5+7yjEuIe)y5=S>3^?;TFJ&R@ZYv45I8St2;dCh2H@~GNC4jj z6G02GvSCFP5iR*+0I0D{m zfbee5B5o%(a6mEc#e*I_fFlana$i4Q#QWn==cG$ZkME`ZZIM_*xDdJa$#R@wwOt7g z4(59S(6 zVV7S$^+a00@y^$g!!-|ffWM3$ahmz6>>#P}+9laHx$%^oDV_R1M|gj8g*r>Ebu~pG zom+bEaYP!G@QRabK}m1Zs=4kXK>H1+ zp0_4BW~9h|!M^+UfO~h@!fkW;$K~-B+Ac+?ajt$mH3>MHGCT>&b(!rZ27g$uTVHiq ziHuqw5r*%ih`797g+Ry7uX#1zL&Xc0Mr2`47CM(-EgQ_5Nw?!MM<@Qm0QA%^-OHM- z;Z((jDtlf(&hU-F{s+R9o3(u(c9VwQ@7T{3dN)9<`g%C(SBt^w>Zz4GNwdRwqGkqT zYSFa$e9N!YV>;A~dwSpbo7=r)Qcj9ZsBCzvL8q97B~!+!rgEBU|* zNXay*2wpTZ9cF87)yZoA3#(J|vW?i-CvBCplG4*Qtb(twOx>0w$4jOe=_FL%{>@7j#U0OOO zN`8~y==huxHPqWbmOt(@_hsq8EHES&Sf&q!72a|Y-q%)P_dZy6jOxJs1h^|Zdj`9O ziI0;3Q(uDIv>XJ4OS@xNyOF^b>#*<$t5SRassq~H8Pm+k@amE=_f-$YM0gJ~SQ8$T zUy@N8&}JpFJt86S?e*rD0z^5SgwAGEU}weTM^l zth0mWi>_-9fPA{6-!B4$bw@12Q~Ry7(UHJLY0~H0Vf)5a39L&$#>~ z4X+RIRFZr8m7j@LH}JHSyWKUWVybi$B;&Y3XIJfcx>IEY=@n!jSPSx@PWn|#$miGz zMQq?!9&@eo>v^z5sfP9K?(OBR4wW|hSg8sw0|c}R^1)wdc@4<}iC&%F-pp+d;D9$< zb#8Bx2o`~KjtS2oYac~d?gBC;j^-0#&Kk&CNG6E;{=3)M+kbrSKC5m%UB&dC!BqrG z!o9KwclLG{J3=rtWJp=vdAdz0`QL_^V9z9e+w#aLSKJ%P5hD0UtpDsXQ{sXN9(Cu< z--Jxwy{J0DUcUJ!MiCcCt>XM8NhlhSwtPZnW;Xy#pmSdoHz{@NcK&%`SK_EBQZrC% zemh*_?-cuCw4Lh!<7vkZ9(-Z4E0QPcd67Y9M2H6EJf1dTU-^?f*bd~Ghk8!*`K{i0 znv-1h@!m$AqeBG2@5e_Z@t_?cqgD33!5_kbr$hwwaQLR}{QF;iKtyuFs?lu8Tmr(E z1ns&1o09mj6y4z9RKuAnoEGvNcfC6!Z!+RP!=ZeIEey)3NTI_C2^Pm!XsZ-4FL^FH zA*&giI^R!oJ}HwGnqB5Ou1AC9^wYdWGf5E3fzE5;QW)g0bX3Hy2eQkJaNcdn@fR*d zbWTg4nsgyn1F`QJX5*Ut|`x3(#E?!sh4Jf~Bnp~67*+?AK(zW1Eu^Ji9i^X71k&Hn()zvE; z=Q_bIQ@F6E0@?pGqj-*-aK;<{-9yE{6KZ)H%7*V@6n7D9 zya#8BG{L%Xv5XU$wz~v)j|u!=O))3Eeeq)%C023ntew5#BoE_%F&14T{+pivhjleK z7j&S#Meb>?5+7Hq`-GgDpPZVw??nBihQ^t?Ds^lLHdH_G_wwm)3erbn?JP{x(o))i z*V@mPNQf>}zjZlL2J~C=`U|oSxITcT~F{Y>QnHs9f?SE=O=msZ-XJ~YPyKk`H8eAL9Vh+-@>X?^TJW{aAfCn;rYUma=md%dgj3r-F z?h5Jvt+cz~kmp!#B z)5o<=5HIzrQ&CioE_4{RxjWtn-yK20#dD^Ubt!Cr87Mm2tMSdS`qpafKV9kNAnLNF z;DbjLx;z;v&?;|j%sl5kEa>Se(OE7V@4ekLXz_>0L1t&GN_jR;Ls>g5GX2_LIEvpZxsa}y#U1%3}t>3eN> z8|SJ{fRDFS`YF>lE#BYg$e$D)_fQPyBX1GxTwy?xXinD5dh{AN-$0eVx|%YS^@~C- z(n1kuR@0qy=ecdty4%al(UptvjvN{8OpdcmQYa1g8^)$F(NArMq;snJ9;5M@4&ob+GgCH0cr1WH4iRO59yE1RGN;`@z1#3B^@}X1M_Kdw zfcBM8@Ty8&ZrHn_R@|GeOZzwqyhi@0l0R-}z{h$Prxu-x#S2*QzY_83GoB?L*s0)# z2{>{(IlBz0B)pG1aF6|H61LIEyS?iPVwD^os~j5PfB-n`!R#xZKt{WLF@Yjezk!2pG=j$pxs(@`FWvaYihE}Ly!>ov3I7CHxK zSvw7@0;5_YABF;J*!WM)JEkaE#_J_XIL6}{e%Gx8<@dd=C`m)(rHW2(*oSFvqu zEjE1dNRvHPnf+4J*ub@Jve|r&a^Ty_-v?MAV+q+j#Y)OUpWxewHqq1cUGaF+0O4PKkqf*tKoe425(!4+9c(?{Nu43?h80cVQdac<+z zb#kbQ7fZ=P^Ne=YwFh_;@l=dt0@~C1W!(6cWwB_mzGYV;-l6*^Kg_P_DF?17MQP=r02sr=+&rHdH%($~|v3QlBhCuK{Q}vaI3o#(VHp}ScT8ea2wIIc3Oq=FJi*AfoYFC`MfPl!nfyg z{6%WueQT^@S1p<`A=NB9h3e{G4adx&($=BwY!6SOdkpoB2OJAI@2;jBXor!r?+IG4 zL)h;gy?QfMK5WgqD<2bw-{<|aK%Q;6h+VZdM_xI?aA+g)_3~plNt~i7%CIU-X)01h zH7QEy{6$S)5yz+YDn35zPd^akG`eFdb2c-UNr_*d`u|~FNgrHHRR_hgzscXV1U zw;qcsw;J)S*Qm-*=J}d6Je0??AN+bB8Ky$J=eb-`pgc^a+7qYLX2EZt*FPGRr!JGLXfN{|7xX2>6;%t_m&NgO{T_3^%osx1 zGTf7Xc<+KD_<|xdp=y3h)KD%a2A}M1Ub$#SVnMAabH_|tOut*FEYBs~NppXQ{!m9y`^+0NHw zAG6^&KJctU*MHZI)YP$_o%x^jC;J8Be={!KQsdJ6WY7DtUw=_IkO2f8&F(DKiOUhE zzcPmI0nZ*2OyD>#xT`#UFdLZiF+j}XE>iN_`O5aeWJ@(F|_2407B)vv{)_S@~ zL|mEmp)-rqu2l~t=l5A_1qku`id5*tHL z)}8`&t75KXAtU42><3fFi)d0Y-}!hka713^KPURdqq{$#n2rQ1eIX|$D#-3gV0(kB zk4J9m&&iC{2%DhW$K=kX^+v$+W*o=4L=)Qa}g zB}=+FuGX8z^mC>gsJU!0T7Ij6lQ3+JeF&+YVc|>?#(K5hwg)Fqy-<9i_d`W7Uv?}z zhA29YRZIUP!6Qxm&$PBJ!CiR5(^hQqrRI2_0ehmFGj<^6h_gPL_yeaAjBc^ygbBx# z7xc;e1!_$DNwli%%EseJ#VTvNLiLfYrCkyCW&MM_R06UbbWPhVx3G9DgC_P{D;(2+!jR>g%^=S9hgV$vb|K zpL;{kdsr!oNMC3?s2=RX+h()JOFmZUKFvNG`CV4(uov|2 zSmIFX`t`3!^39)>zwF?>OZ!Y93XRRH2eisP%~F~uG@8hD;4=!yYbIA$Cs5Z|(bRrB znEFmjl`^*GNnYCXEcX}YuS_}3R?IJe8-cIMiL>Q|PPtMFs+1sZ^OxfLEF9}N18EdA zER@9BvefXp2}DCjQ=x1E?$pdTagcBFXM^#T%4d2P!iF2|g z0>e#GY?n1w)|Mfz`Si5$Jjb%Ii8>t<{|7oRU!uP5H@ZSs|B@Wr4(-kJ6L05Sbirm} zs6YMWMNqwTlBLZ`57U@0ikJJvW7TsD#ftp*chd5CYb!Oc4R;5-rgnHXKlx`&UdHH- zmefb=sJk!ldmqqpZT1iBV)_^uhN~3atY7uY!rV^6tdlAjZ!@tI8E|x}7FpkV_@;P) zEcB`zdfS$XD~*;_qkYR_iz(u?z~mQeRD~V(`B=T&)HgFu&E;X}!~Ci-yM17kdVcD; zBB7Jau6q#8!Nq==l>Ps)CK{5V@t^EeL07Gmd)@1f#A+7{9lX#RtFddl~bPg=+*m5}!V_mL#TFOU>zca;c6@o0cQ zOSM443$t(MiPESLPkQj?N*6&2z#^n(H0UPy>>C>grS;|MZp~oGekrRnfLtGGf`oPc zr~9ULVY8&!u4`UTgmI!XjF#hfCWmv2O2j$$hctRK^xeFm;k+XzvnNibUz-ffdB9#0-T1|2(%m;)6NCn(|!(kc4#3s0SfJ^ZQ%&G26CI& z1A3+#B*k1zO8_a|s^hPOYf2_cNbjiZFw%L8$jMT>`Z-0H<-R4q0OlxzIq@W=7%l*n zLtl6fv_^zNgfEOZhG^*#%xgO*Je$bUIBkZVmxP-E??ZtBnf9G#bl|mGndd5L(APrT zL)vR~PT(t|%*p!z5OAf>y4_3=@@|O2xG3`0)flQ0ONArvTguo&h4RNO!q=-ZpC9!M z`Fosqi|Z%OriTPoZ)P(!9Ao#bnw8GpS2D#BrI?91-aEnym2)1dxG{(Dj z(Qcy9d-IcZ*GUt$+O}bB&MEM%gZ`0P^o#p>N~~Mz=vC#sa`~u@#Kto(`P};_ zbd8ugTkGVhf@zdY#n4J2MkfVUkp4?rktB@So?lZm$CS^M-$3E3sn-6R7tQ&Zt}x9`W6` z*WgpOKfZfz{V=aMwpn=BT-Sh7V3STsT3Txi+Q0LTl`NFS=Bb~$K|l-Cm@WCPmTsJe zw~7A-tvkzV!m*BJUzLzZNr}AzeB5?;(BUU@7h#p%#~2yxbH34LWqbVR$}!^MjUQ+jz1+{(8KwRFCNj(WZVoXZt(Jm zR!cLrC-F^GV2&zemY53p#QCf)wO$J1bU{s01uL^TB9f!<{1Ui|zdjpm@Fi-Y*iMn; zsPJ_ClbF|B98AKsf#>*?4dEPTy*pPd^iwp?lOcJ?UbIy8XB}ejO18y2k@xg{U#f4W zIfqUjVw`gnHa?psO>8%kfpFW%6fi6Vi|@ajx!ng>t|cZ#zY|DcNb~~4eCe#Dx$pYT zorzLD&ajG|gJT&bS}|a&vj@Eu``_%6q=P^XqU_S?<^Md=Y`Gx|OkNtgKLVkL3i?O` z-6@;Cl$4++xcY3LJrNds7gGFM&uHMwL4S{8h-Q%Jd;mfvq7EPkP?01%kYqI?Ll_13 zf+Y0h`PA4aky^Z^5ejS0i|RRrkITF}c0k!VNAwbeUn+ijm; z^<9r>;V=NzUMPH);vgEhzIFNW!f}_LktE%4_2WA+qoj(&C2@t%qLE?yxX(_uS1u=t z4#Zv)-dj0W4&Q5Z!2RDJwQEn+nRGmA_Y>(PV8q+ZlcIi|>M;$zqr%V<`BQm6$M+;IOClgRHPfHouPrEf1^YjzmNLF=HXkET?6E~4T3mH$4!uszr$TGqB3!e97Wwz)N*%?o(ci@*tP2X% zl?^;7hH-@$Ex^6K{6?OFVWNnhp2EH>`E9yhRP=Isu&e%GRErA2q3l?l6?&i*A9v@k zAC!?xOFP?0G3?_|=_HvpERo@akZCg3V+;dhNoDk~X`2=h?%@5F=ruuA)`oEOlav%6 zi5q_qohxkjN=rRkGe+H9&o|qv)fx^Al4kT{yP9n@GfMk%VZa2#xtD8i`(a%Vd7Sq=ejG?AhT2t`LzU0r1z}Ki8LsA`0d%JD<0pig8Zv6jUkf^ABSVA5 zozq0yyQ`P)2^Gr}`RT4N;B%2|S7)p9v(Yv} z{Bnri8r9H;+C7$E)}auP;4Zso*SFI3ocCQAE`-AE=4Yqn{(}4wtAmO2 zk3^l#QJuLwQ$deol<4#V+tzu6@7*He*`?;7|2=fVD4qV_&`C4N%Jss4uj%19dcYsD z0jn{pOEp&3G70#yu%$lon$dj44zbHrw56qDkG^w=)+pj{33LZ zIOVMC+{JgF%GdbVh4S+n=nPnEOfIX72|hOE03eQ9h1`&D7@u*r9tDyj#TcIfqN=jQ zBtx70Igi?>Q@u~Lbs;H34^m3`@YNQ-pb>t0CM=P7!JY-su?1@|f?X`!)^Iz`MyegG<1Gy)Fa z98I@M5kEkMZ;9A}j2OXg{g&pdujr@hK0N=lJ?0nIRmm{vrFK~j9rD8k;KG}*&8{IQ zwzHPTvzZa1#+idTLMABTyd0PJMU$a4eNrt?`czfZc~*>9Kx;2Jj`JGXQ3X8#tc6~P zc(-HmmJ(E!TJldYE)iE!P_9=NX}JDoB9vUI?I>YUm`*JXB|ke%M61U%zpq1+{KqV& zxQ|6UX-?ASPV?O8vCPAx4hqy)Hl-A$G*%WvSDjyp@r^JbqTqEwJ^=kjOH8urLK{>yLq*U`;J}iwZe4kS5nDi8Nco zEyK$fSgDAOF9`bj<$m@0{Sgt@!&TDF))IXli9yYy1W(9D?D+%h;>)~58ap+q5xfdQ z^M2Rkp0WG;IQ~j;vxYOaSl#&=&+L1JZS;ylB1qaIzpP5SuOf-hH{8l3^{x6d&+6ZV z_WuY)xTxEI61oRI|H?*2lK+k#!w#O^xaLbH4xRYh_@BIPzXB0jD?_n2>p`BCt_-(c zd%T#-SAfNyJmRP6q4kyN_vT;8*MYdvF%JQYMo`=c0iV!q0kxEaF11{MUmrnUyiOxR zp@Tn$ykpm}X<znh!N#=?=L$g8rY)QxnBK~x^40l^I#l?5yAcld6ks#NdmdCogZBgF*N}Y8$KauB}5L2$J z`AYoz6!-T*xe>VLWp9xaOOGyb`q{ei&yA`gZksJ%eh8QT>5etQHXoK2xfzXfZcqJE zZm2;G<%CVC8;)mOV42~@7`^cXK7NP_&hpXHu?_uA>=$J6n~lbSo9h07FYPa8Ec_$AjJ1F zN`Wo$H`V1vC-?G#q@J>`4!ONXRHATT;l?uCz#qeeQY7T=Se9+H=Crv*`kV7d8FRVP+|p5jSoT5ID_dlWkJ4cF-;QIWdDff zAbFr%J9+h}igkQ251WIc!SbxgW({qXMS2S$G&w>!*(xqYAx8(77rSg%Yyr;yn1%lD z80sm>{lDRlwk~nJ+86)c?rT~b4R4MFwsD*EierRFg*j+@1>SnqT-gYE&G`3x{y#^3 zFd$iwdmj6^1(++at*76!J~CtSOY$lH*@6+2#Z0S1h>ah4=d|=@aSI1D5@O$VFzM)c zh+OWkmwExhEQo)rg4$(D@}}V`V`^?OI?W5;iLRDHMNn7=Zvty$Kf?I-L=xcpm&}a! z0D-+6jA8SXT1QQ1iy{1bgsXkPeq0rvR0~~ch&Vt;k{t_lSsOW)4$x|$b+}J89zw;1 zy;G(2U=jPRkXeZ=gcF0T<|Od>xEyp$i$S38ddD-E;4c3PrefN<09=hTvWNF^2Wte( ziR_^_zylx+c#Qd?^`suaFlwxq$}x~q)oLAa4BEiedG({?5C@?N0t1vy^zqB$gG5S% zdw7wLkF;xRCM33~k1V)U;&?jU0Ff8yuD*zCRriP!yWOZ^E)(G9BL;x1ej4>_Y8In` z^)*R@$7mCU6EGRM+k!_Y{ssSfx%0A=oNe)x6!DKmhq$9#`e9eZ#wd;l;Nj9tx-(ULEyBM(coHUD@0=9A zJDa}LPz^U9VWFRPQUKS`5BbgDPW%G~+q}ynHAUmqifk~U>h~1c27Ny(6S~F~sPHmUJ@2-{*jTn4; zh-A78|3kS?fI5>GJBULpmmKNBD@=de1iaz*<DYYZQd~u6fMfILk)9dLCuZc7|9-CSf7c_EnQNd~BpizDca`pLGUA%QxEa{#swpeo*d~IqV2EV$_AZoH93HEY(ki zi}+u==;E0louWKG5Qc^x6%W;}6HmzcWLfxs@vO0|^=(*pP6`a3Ihw4{@J@j%&e8G> zif7M06QfzD8^w{TgrT&9xlp<>Uhkk|^qG}6V$wkD;_rL!g%Gx?wR+iy?`DisRg+YP zgbMoZ-^(7;dBfbs(s51w%vf>KWx2aSkry@{y#Qh z$V5b?TW(RhLt2oKkcQDEIXZ*^g8>3c2rAv3qq`9#q#J3JZea|h|DXHY|Ks>Q*ujH6 z=Dq8>&hvboOC4MwT6JPH)YhVO8^SIP{WcoKNZqiPP101!0uo>(bGch0d2xrOO1DFK zgE$g$2h1Dj+wltQ4r0+)V5ApTuPuDVq4mcYjc;4`Xc(Kr(aS(w|>D1f(f^Lr|-yNq}rmrwJXm zRW=J#D}ok_jG+wUyF-WecXBw%yvKAnJh_^ZLJ4jE zySQBSjoZI;WDu|mDXQychllgEx||f6NFWWk(?qgh1(Aca6@L!;D}$Rn-nPfF_gZ_L z_i4~@KoH`LOE3km?LBj>jGEeRBkzR z9i$~MHOlg*kj%Sd?>k9lUN@iF9;O@5wIWjL92YU1G}9%B^TH>1)qjiR1t$edin3-6 z5(KA(i`wd55+{jv2b)i6YZq6=7Ph1YLkF>xM^ryDqQVfI)4tMDMsj!-N79`aM(%`9 zK}$Q@Tx_N~9bhT7*HJC`+@>MRK>}bU(0+w@by+@8q-;rEgE!bBFV130rjaTB zZyuE!%c^aa%U5WITu{mtbr@NT=&smPeom@v*g;P6L_bdk*Z+!|vkzj?17-~oXT@h* zCBGM1avkmy`9|j@GrIFbr{G;VKWqA%+$q)-7|kLglHT7}N;|FQp#58NZctn9lW(!b zALI?`1l>RC7v8y}^8JetT%O}$tqV70cu^1L^=ti6Oo6EmoLCpCVru=y#K;e^hCN>+ zp_D);9~n$6wJ093SkcUB&rjMfD(4)1`0zz}x#*R_N0)_8m0_~0K^yuyt_sL1WQT5h z>gOaImbpP@HHXIGPel4KE6%fQT>X$B>cl~N`FLu_yFb>mbi(XV-cWM1QYn}&Uv-47 zbj#4v%Fnws^ir>+-8U~J073`!*-yD_%150!4av5Ysmj;cHQ3b4`SBd+mZ##pMCsH&&Ufyl~n+#Ry##Iqm{!F75X;zUoTKB8}$Uy5SfJT*w| z8s<#D1}Kz=OVAvn4v&`g{uRLfi-SZG`rrB1v|zJ0|C4X^u}+V$h7C4bNT{(9h;8id&+go7p2Qp>h}_~jEr1M*XiTE(BeTVpoI$EE}3Y4EXX9aRza%az1z}K z`(KLN&Q3}6<5A)Vy%HW^Cs$%PM4i+YoETm1@Bx-U5g4lJKzMg0!4}@z)dlg34uj}g8PlC= ze~h4e76Yc&B}}fu`t9NngpPiK>69Ht?{v( z>2C7+IV`%_GR)(2%N)p^$&4gb@hhlpoj>9iMY%=4p`R~ez7*Q&s1p>e@ocqzw?BO{ z96Z;Ii^;FwoBmcRR_k^74tDhJaMme+19*q>IBC3!3Q!?C)!4Y#LPcEjZ;hp8za@IM z4q2t>Bw+MtD|FN9AFmpTEl8KJMaKH-=xSPRC_YvXGSY^7X|FKE+h-+L_}ye)1r`R~ z#9l4c6n)hOT5M#4<*$xoz1KO9ei)LgXYyfOR8`EKjhNI1Wu%-#>=4GbImdbg$MG)K zenHlM`<2O_m#a4v%kZkzW>4XT^s6+Fzkd?P+bzL_FH0KI=^Ap^fK-X~v7(_j6>N%? z%&A7hHYY3BBA-Lsm^}bFxApLI`6S|4aGGq!lv=angr-oD6@aLHPvDh#@TssAs(nxA zpU5|M%=$StN^Ri{V}ki?Ik3%(5I=obN(IlIio7okkKAw4lhmG@jdZcI!jdE&Y0Bxt z(~n!Gvg@l}r59^XO=|yOxc8h^jrB9j7uAySAG%XQgBr$`hLRR#$fU|b2VQP%8b+ZX zjbZt1QrRy!v3s|!TL=2Zf#2S!Mn=smRxtxo{(@N1w}aQjp5^245&0-jr_q)1+8uwl zJRh{X1boL)-E@Ws_wG&NyGPXYi8Y5zGZMLhWp`nh1oJbtxrnd%7hZM^&aENA zITG^%)6H6sTEzsGBJ!4rXh1oZM?gJ+eJ#P<%zOuR!|bOs&*Fe>3lvs4dW#v`o;B~p zFlubNke9-+P&9`eAR}BVc=dqMTH!&EEX6k%FgXktSye3q&!N--Aj^) z6&T^58)hXNf)7ZrvmD;-(Xl>#_u8&|>g=Rgj$Zu`b$Gn2@c(?A44C@Z?|6s&2aPR& zX7DmN<2qh~-}$CRpIlcYQ6Z%+ei~?9kUW8fL4Gkr(tF z%>g3B{-*vD2r2|wEp!Ea^ohm$fJVehoUeT)XZ-vd9F9-JLo^_Q8Asbob8$>mz-9e! zuo;HCylDE4s7w-&1mokfGI*1D+*udHjr!(rS~Vz~HxS;SY+;3e@{$4CAyPu}r}qUi z;Ho#k0iu}s2u&0rh9)a3l4f6F#IeeHar}O+VB^u-1Pp1{0mo`LAMyP<#2ND;NNKTY z63XueAl%>STw+gGL4r45_@pk(I6$;mCbe+-6FIRJ>Vt1+DQ|qnhY!L5)PKXpP4Der zhJ8^D5;H}qt&scTUW{beo-d?$_Khg?($Gyr!Q8gqEQB zpEi4}7c3)^R=1TbHF*rDP*&eiiSH5{gG=r+H3giO1{Ekz2L4ag**W)FMpO6dz6eT}I?hg)xJXUs=iVr?^!42N<3zXEEEiViFqt(p zFHpT2b9yL}MVAu2yRtDf*KYOoo%6hzNs#JXt#8V^y@k?!LlWD8d`L2o@K*8rL_X9$ zWiV{TPps>*s`8XthsI8QAw%;!O{GnjTyR#)d_k{s=?0q;f@2Wk_u%;xM|vMFbD?-C zYt92DC3YQss+f9~tmOV0Hsvq*PVn`o{$EL+8&OpUMR3GBYn0pVDjN#_c*RK4BLXGK z+~ho)lcxGs>=q)CN2C+?TwNpE#q*=ZlBS%iGX6#!C5rt^I0P@}ZivO}5KB86k0-RR z+~nnXmgQ+ zXN5Psp7?#Q-9;xD99Jtp^S)SBY-6`{kaev@=VwOkYPTh6_o_cONINN^GY2mIk27QO z7dPg7RaWWp?>qBJoP`?7Y}d_M*QRQsQao`bz3_H8ORgisKw%FQUPCRlH+#Z z=f2&0kqkt$UTlOQRA&Hc(pJ{xq2A`Pv%N!u@}rF~S4@D>H64U{k9N%E>^+N*9-_)C zn59X`-s7Brm{Y$z{d9_YPv3db*|(V|j-EdtSAKFP`X0izMp>eDU~;x{K|Y5LE`+&x zx=Q`asI{$>de7K=(J8EX22tai!=hsPNJ5Kxe`i9`rnxDhd~&>?XYyw9gHJrJxcr)x z_#Mi)RheN-E85QlM(wPH-BV+${4>Djd>+(4o}n!}|7>!)M$x32%VfGqtL6HmooELOsa;{vGv$ z_Xy}65K|ekOuD}joitP?;Qj`laYH_B$LfN8AX1vqjFd6L?ZU;WOj>9`Jy2U(%t*SD zWtCQfCq*a zP<^xoF(YUIJMdC?;KN@e7-Tns2N(2xBF|PCZhy)M4c7wY=|_|#KVQ*!m^%$7_=C_L z0vx|Uq0X(i_}T_b`a5}`$KWosHim{3l^F(6#<1(6Yb?`1$y?D+nKz+eq4w*2XG3Ab z%;!!`($Y8PX$ou0x7gb&DbAl=Zlr`ikp39bku+Ctp}`Qr6-gfuCh?I|Jtkx#T9BZI zSL(zfYQf!x8`N2$1o5j>1H6yuk$tg#%CD#mM!t$@l&tC6Y_-!ZFFCTut0@bD0hEgw>aS+8`^31Bl=rEK7G>PtU#?od#l5RuzY^JP(~A#-P<)aoh=9J?9Y3K0 z<|dQ!LGc21{%0QReZNW$>cTwEfASiqz9^+2Ngs>2e6!PeQr+aeu%;$i?*8n}?%vo} zpQEk2#^UcZZAcu)v6o)E-|K?s>a7$0r5Xj(cp-cynCRfbIl;SnyM3SN=9=xo?lXvI zF8bElT1+L%v*_*Ys-13yrj*TG;bR@XPieC_ju=KHL#4m#1gTHTpqLvP<&SN8^o2)q zEj~6psjMJ=PD&zQ`cIduFAE*xuqnNs&TH+wDc0)y=F9*>B(%(64T)LTu9z&479@Q; zuwGiI`IA9?3186a9{@dDqAu>x^W=#V{OE%zQ$XI;4IloKb)u-a0qOyxo8Z0AaB zYuvoo+ILFlOA-VO*a9#{Hw_AbaK)Ds0Rjdk-ZdH@T@W`M%^;@=(sTPK@(ja+Fw>9( zb9_I&V0G=37U3+Hj=@C?9#_?vVh1=g++M3ULA@`bQu;2%idm9rAYZvX+e0GnW3Ha* zw3#}Xer7Kc1;=-Lmp-DFJC`XgIDAdHTSe3yP~5LnTH?s@O2BORwgjcNIyH_#-uMqxafseIU;$^L)ATEqgHUM2Qfc6{#ZCbz1rvZ5AMQ}!xV#7R}~a9-SpIy zQm;L(u3YQZZMbY6lXdDyZO~>cp$t4jyw;@$7m+9LFxp<11~?A~{uy76$Xz&}-9+FL zj(Tsouxx3{V5wP&E*LQ-?DW<)Q63;@*{D>LH zX$aP{OwGk>x*IEbHcS$HCEvhT;@?2#k`?`UzBAOPN2QskzwEZq#XgjLX{i_J`>~(x zI3CHxhP_$_(OC@`*-c#K;JSAPNAbBt>?J*KO*|>VF zf{wZ`6WV2tuscg2f9H~MB|^v;jbNl7Eqm~rtnM2hchZM#8>#ES+QG|N=YZa(h2b>W zw~JR|{XUEbi`TV*$ON_YG379|-MCd7T)#W_&J-|A#aTWZ!~y0aq&vde2IkQ6DC(3)$s$(wfiS*Fk~S(xJFt1i5ZiZ&LfXH0n?_450a-{e$c zoHhr>mgi6UQ+loj^3$i5;ZHkH=MG8wcX5VHqv(-Gda61`WO*9=Uefg6`25(oaV1rQ zHaQDE{o+Krf8z*AjXG`q$$Tr2ufm3Snl=beShnro`pkC$!pZoP>dzdOXg;@}`v)Kb zsaF<`jX59a0BZyr;I-a7bmcOAu3hF*W02+DLGa;2a+|A`YMucmh0TobjdZw6f4XZg z(pw{=Xp=u>nxW3@^JRw!Z0*UcxNYP!j!0OjEIFZkXTwgiWLf$qRQ;YF!CFz|JU`Y? zkO}`9FGN;8x?=f5qx130fWESfUW~D4lqsO!)3KvY@4ZB4_73*yS#4|xVo7@9!t>)k zZU!S6@8&3@P&sAo!&jeMt?R6XXY6%RZ-kSj-U|;4a-U=)A`_*Ys%eG>CJLibS2+ev zS5%&-o<-I5y#%dWyYka>*rN;4!DzcnYhsRNd#hZ_TKU22&uwwkdo+5chlM^qJ(Cj> zMd@uiJI2kTno$HV~dL;9B56IZ4kRW z=!-hsR(N`H30`x~Nb4npRy;OZ%DKr?vp1X7^VqFDv(;U!wO1O{;hM~!b14}Q6wQ;- zua=kWegwQbTK#WV0T)qmlf$dVx0B#4?T)Jo?_IJIq02(i(nM|qr_{BM`BY+UDeGBr z|D!mmSdRZI-wXdsBLV=B_eaTsT4d0AiT{y$E$I}`o&}Q@LPsGRLm8KPr3VYp_F(se zbjY(cx(Cl4Hos4;O8ST<2Bi-|GVvDhf?QNzAo~N=V_(b|+En(UfLnHXY627})+F^L ztJmh}O7)}ye_vG*8&(Def)E(n^gHe7b%75EfwJQz1Ql;UYN zd@?}g4N~#|_2XgRq>J0lKMJ8J>=8#>3-WlfO&`sX;Ap{y9FD3y1-pC+1@?vP1Rctue?5pbklH zN1sYdNHh8HlQ1UCBO+IaYnk&}Ty7yh;Q=eOXZnzp3KdX9vWG%32!RDUcaN@xWAd*5H>t0qpyz_}S^=Z0$ zsi)1V#&V!|*=y_!gIVHPe-gjX^;)$Lws8};0o%m&{Ma1A*|qxYRG9dl#+Zn?kM`A= z_`EaFQ=tmvacM*yC4T-Y|At{AL`&hM^CMNO%U(>GcmRBaA!)3#HO%vEJ+kQZU}6wB zPuE*UpE}HzLz+!^xqF17RPQ1DEaH%3^FvSk0f@e{E)ShLLN+4Vo<=8Qs7NS{?~6JY zofZp~CL6sv3!NSZxd!8dic!`F_tWRJgDy}C^kW!})aZ*}Tv-y`)NB9em`|HifNj8G# zDv6JIs8rX3EnijT8_#vNR6N6&MVSh@goYqr!>$Sw>S+aNrX0q-Ic)#QZ5V?gB!gVu z_d|%11V3p1#nfgL^bfZ8GiTJxXJyWGwx~b&v#rr_7&nqDXj1(~$9kVlLMXYkU9_-J zLW;*Rq=TkICMXzmlIYCh4DOr-Un%Bw7&;0`oUZIC-JMcHbNyG2!B7RBKa$Qw5K6jeDHD z4~yV}aB*839_|EJ+}y6V7<`S4X#K>Cqul2AZ1R0JH7ijzymVK~M#)&>(a!!*#z-#} zQkE{58ZK#TZnAu=;dyp1`SM!m$(Y&g2Z{D*pWw6s!JoJW02&xESB0HStrXVh}d7pa#b+w^@|EJrEo zU8bG?p&cmBZP@|xk$l*;c=ynysk6WTq0+njKU8`E(a3Neq6t4ZenTYn{Z=SZK>)~q z%#!$O&3tP?x*vCZ4}761d6L#}++h%^*w!I_VPgiO=l5G~`2%pd}~>tq1&$ zzofG%3afo&c4tOQItB(0w4ye<3lo*58ojG1AMW{hg_tmOoA3em=cgM2zzI$-Me zQ5BScB+o9;L8eZ!g0I~*{t3wFBj8ZJXD2TcnNjAmy|idsP>a_RvNwGZNau_GF21}z z3|I!gIPq|QvYrHP21%ZTt%Qf)H0)Zq0sx{lUhWIa`xs%zBq*Zy0^I-Ha*=1v%qaT? zyx~G8A8^4G4dXkghhLI-X_keO@%XRX%mQo zH@mf)pSE%Qy(c@^-jn{M9G~qIQsWo?fNZb2+np2U@$3EP3I3+Pdyyt0NOha&{fTw= zUfkYiD!Mt8BGl_}CQt%6M9=8%&sAzQd+p5>*M3c=T`rV!m&`*FlWd*RNES?AAd~r< zRf%y_g4WbJ8D%MzdXaEp`DOl+i1@r;PGR zQTEC;hS7xb>iX2Wp09_dp4YmoogUCjrg!8rCj@`+afY|GaN@=6Im-Gom)#^z)ATjf40~ z!t7sj{t@)7tz-^N*K^F}w*=t5wgM1rzeNqVE2lraDkX*v`7v8}^$c07Cb~WZf*^Jr zMvmWYdSHo1K}0$mFHIW83lw#hlE)5-f4URkAsaS+ThkETaeQI*4Xs9>0lYU=$M!n9 z-lc}zqpZK3b$`y7jVx304#!NxF}k~LP*S#zn5^`OyNJJ6 z60ogE-{u)v*o^4A`gy;k*?H1n!F9vLS)pB2bGWMr*J_jhbZxSZn4u~a zRfxOGnPGfojU*?Tk+BG~2juP`QH}<*D(GnksZ%D1X@&k9SB0*-t`B?*@3&&0DIqQ` zj4}9z z8^b^>MYkC@69H8|5Z21n)q9d2OlE|-pQNS0=v1kIrD0M%qZN9mZx|{^m$9dA-0>c% z(a^V+_b|Oc5r?~(iR|{9)dGo0 zrw6-+#6-K<;6WeDjwYNEUVj0P(Q>>!?0k8=^cCqszysOfB_9bF%s0K*L{>-J_WnJQ z^_^y*8->MeauAJ$@D+qrH{{$eaxeF^nq)$?%cUd2Opp=ZNO%T)uNU-NQ5!E{*d@QC zNE4}}a1$|qx$<;Bjq)_f0=*0|#9E|@5cdojwyO1b;clzPMPgZMe^+b52<-%rpWi-C zV)i+jwKEnE(0mq6KXzjbt)W1)EY8<>jl8>*Ihgf?Hv?g?98+)2vn7vq`UafIqJ>aT zP!FceF)c3?o|arSWUnY(D3qi_&am}rQc*GKy=hUR-Zz(yrZ3>*?8;aqPomKViTvQ( zLD>?fzq0B#n$hA$myWrx=~n5%NNFX^U1p~0&yQYPY1*-` z-4(&>i%1bvdjDklA;<41HY2NPSfSqf*Md33%XG14BZ1jteIv zZ6KlEPo{l1w(JDPGo@8a!Ra+J{+LHYFb}c~-m@4gu_VIXP{a_-G+`XmP{lH$3qlMh;cL1#Ydo#^v!2qZgj0W9gEcx8L|Oa;Z$8A(|n;33klM-*OReaa?u_S$j8t- z@|+pQDhlh@@3!CHAX{{Z_|MV~Io9y6KolM*Mf>~LtD@w8IIQJhEFoHh5I|h5$_5N$ zW^aiTFL%urff5f8lQhwLQ8c)K8JCzdg=KSajkh5Ljp%#hDWG3=Fc|R%N}}nc>Em4q z&4~I!X`XjPI=f^}GTi)PFn~iVz@m5=F45gP_bBwx4AZ6uDq=>;+YDa%9i-&G@HP#K zz7xPsIDZi=^%t@`bZ0>fd7K*+K0xIcsmf3T>?2;F=q+N*lkQ|<36Lqg8US+C(jSy= z4SEkoAt8+qrt#87KZ`q}zexT4Msfn&cyFWe-OxhW$KY=j2ap>LikHv}h{zbjnTXnh zfmaI-m37Q61lJ}FF5e7x%pD0S*Tkj4p%rxv{b2q@9|#jGlqFkiG-?w@Xh{-NFsRQ0 zZUuQ@NO?#W7pgtgKjEM~RsI-!#A_5I6FI6TiwkJ==xO5NK0fK1YA3f>eTKTHHo#^qM{ z{YfS@iJmU?54<4v)U3?~c5+~C&rbbipuJ%qD zWmNN&=QV0X;fUYm2u%v6_(kjlA_4iyQ*^QL?Vy9uilKnj$Uf{ZGf}7o0B1h+6CF;4 z#a;sYf0NrMV@8sz&d=}hzkZ7;Vz}48dZZ7B!m+;DLZDEFL~G_v-J<^7h2GW#)g*x? zH~9?rM=ah1yLfjZ@%f054~06wo0U2VQ-wfVv48nU-Lt>=(;v4si^BV~sJ^zd6({#s zu(1WPl@k??)96NVv$ab(ZG1=i*5>;UZ^i3$BnY_+j(ig*8NOJx3YSj|SUCOo)WF>_ zN78>@!EQNW_Q_h0QXg{Xn(^yFdEy$cqV|%JNh)<;uZ+27 z0>Hj9?Fm02=AfF1*@gi<#Ob^^&$W?(90!bhoM;B`DhE~FHy)pa=pwJAu^%;%jau%@ zrh~R~u3EuC9mhIVY}xq-``t~}hy857qlgMIKn#}^A6%C@SjuJ`SG<)9~fLmSu_VH}lT^cP~#`T*qJ%z$2Cj;Us zO`PDy@Dr~F4-KT2K#z4zhQlK+JD4yFXeoI3uNxv4@F+kxe4Bbm;Qa)s-6(44{h~>L z25W0D`~{nVA7sPS2}^{eAG$xm_j8q8{P^gZ$HpL)SdUj5mhLj`r5PdU@gE|Q59w%j z(ETQG&M3o-t{Gz{sh(lSDvfiC`7dglpLnB`5l8v}f*$eV%|WX4PU8v{=;d%t&WO}y zwN$lJcZb4GWWISR%UVEjm{?t=trY@C)vTy_|tBb{z@V7|ev`wMkQXd;8-cJSu#9NuFrfgw`4L&i3YE5wShN#m1019jrr zG%NwPU!8zEm}U3DwtU{?+KIB^-m2Z?+K$>R--@c{o;{u!HlAj;F`bOt9Nq>#yEvPX z-P(zf-MFs>rQJ(;o9R;_)gwE{u#w%tk6QnBkpYE?d9s%PTWkqJO=naRCRK05&|GWC z(7pD+Ci^2iD!=dt}VaprPtvUMDLss;@YPvtN%^_$H}Lg+GE#=~qS^#}*i9BtA3w`|28 zEcy9!H9P!w*;PIDbE0PpYxQ%W8!5bbIkigN?)h!AEAs8HdUAhYLsA^%+TDY+&@*S+OO?U>Ge z4nwvE+aFS?E1bn_dl?1iX9PaY*$MEO%!lNUv|R30_#{Nxx|}!2S6un}$e<#61u6z7 z1+7r|k(b8G3CTzFQ)vv1dbrx^xFUY3P^^>sd}m5*8G=vhEzTYzC}kVv9#@)CqMbjq zm%viZO&u30oQRsYE&Wq9)~G}(MxCI(cwU_ zjVIK>wPX11Ob2-;bTnLi9YoCdASP7YN}2>j(Gkj5W*6qmsZRL!&H}g}ZxiJ7Of7v< z>M!)R!^B;Pma7uJjh6>3L~NR9vIifI&?dR)XVApd%jX@$wjqMa!Db!x8CPr1ritSa zfc2P^v6~;HlqH2SBO?^Q!b;t`@8&l>QyX+6{ds$rIXIDygFah2@45z!f6R74tD9*J49xu5nPM9U$?Ir#j_L^3nBaJ){jn?7AQ;WPN(V8U&T8zk|MmE z+4tNT53OwIy?m8^JtDD0g&`b+r6n?)=`$~pOn<~>-ecUvfYWN}K;@%g5>%=uy&cn5 zu&Uq6qQi3IpYS%{13}d0)vnK`9P{SL&c6HR$wnjA=Q1S1=dxQlf7q%O`Rj{Gz%Tq( zA0d*zOT63jHY&5#o4DiZ&69C`X708^JrnVQ>RvUw!#dPllT*p*{z6Hb;k(@Y)tlMJzjpn%1ZwGiC+YgMDXRTc3@pg>~S zXDyM`I%%#QHFoW|FYV$*(snXqO4v-4wPnaoTwe{fUERy4Pkuzo9K{Az=Dw~bdgLhB z|H9c7hILCam|C~zEL1MA0MONifzNYU)b5O57-@ReTIb{rS$_y6Bf?)R`3L<<5$OCW zZe@b)T?Llty0-Z}_}JgC6c?`p7oMt8YS*_ZXH)VkX1zOCmBdN^Yi@4be<4J zxsK%*!nPNA=!DN6OFknJg67{19=j2wPoxnieF%#*380E1kJ&1+|5BbWhv%FEZX-W$ zB|c89J^K6TnBaKx2oKUKh{t~C`=6QIwUYkgeDM-9tLm{zT{0^>o$0r0u=O<(8%&7F zYr8n{Dc1=bnO|n|u2>Zj?ij+l4skQYKRdPDs>XFgO&Kgh3)aGNC+AR`-4au~$su>= zQO5|UvDW&foJ*&6y_um_4Vd-v+tV(b&j~x-^w3mO)4Rx$X4IfTFX<@wFF}mqbhC-F z=#1^r_-js6K5JtqXnZ}w`}`}l$*Ct!e4=dW6FqRqwMBZh$9oZ%)cbaJHnkPV3!I!J z5>TufD7OQH6Ky3DiVaODomRXgilU~I7cCH|@#{A@!EqR4PV=I-0@eJ+TK)*zody{S z9>zC&O!OY;O)Q+-+u93^JSkLkY|XY_?x`Aj$IbF}NU0|!_JhE4sxlom5mQpE-_;b3 z2uVYBR|uX+A#|2KW`NJEA2LXfk{Xo#KW4yek^f1AO8$ZU4iDpub-cQgis|I7S>Z8Q;WjVxA1{iB~HqTftzHvXZn zo|$!Sft?JbQc=)>yro5L0u^4ML=*K0Pb4dN$~)JUv1W%u6vI1-SW-0}0Eo9vErtxj*cqK;jv#8aRsBmut+0$fOks@sl`<$q0>)%55PR2cvIyOSG z;{~=g^4qyH=~EO~y*@pSC*}I(Z0uIYaXReb%?MTa4PSYqp5>x#t4`dp-sKuA31BDY z-Q7=UfAZG&t^VcCF&|Q5>i2?Z^!79Bxw@yj0yd|DO~m~3y=}Qr`ljU;%7{sI1?@=# zU#_$Q>IVs0j4|pU;U%-1ND1e@NHQK&h|F1E zs2?Ai;w_B<1uE})2br%0q3fdFqf!s>3KN|do2-n)VhQ$0R*p{#CaXQv7nMUXwZ;LP z4L;5CQ&UR?W%r*jcovn5k^J?Ek227k_aC0!-O~-|wcsCqbTQtQF`60=Ok$m3o?W#h zJF8w&#rV}yj;ET{)HE$h1=QLph^p!EJ2c-O#xk;0O1~*G3)XCl{XJzT$L?mmEX1a} zm}%z8LZb6=*oZ#17vrq|`rP-hi0mu3;AMAfZ-D8)Z_$5c)g>waYaC*@R{XyIw{@!`7g0KRtVqQuheMiN7D)bY)hL>wJ0?AKdMvO~Sey$Gv z^L|NMe!=Sn2?OXC1a3|YpjsRkYKYIz>XjyZqqi0QqXo7Kcvyxk?z4AH*mFg{0TI6J*iTD zkdzYUV#S#V+3htjt5u|%Cf#jGvXb0Wo=#{K z-EEdhRG@z@zjXKPImF3bb>*(+1-PwpNm_A3o(i`>IT(gxRts<2Ql#^8GX2#o6TmeB zNb7n%v~=no@jhE>R7j6!BNBi~X+(eTvx2iPEnK`fxQ)idHbMf*qEhwJ)4S^> z-Qv4fUZw%j#meH=S^|d3WiHR1{M9K8cAK^9UV08yKUT4hB@$+%E7cQ<*W&tI^^#{? z!$=)#^E*VARnCu9j(td$Rr$HTIeqes;y-G(fyg^K9bghzy}%!m83Sh}UIz7O!fayl zFQisATwm)n5Y<0oqeQ|z$w-Y+OKj%|HqO)%R(35v6)& z&y|OF173anXUug%si!J`L{}#+1i&jhK8Vbm$r0Jy`o%Kv!acBIhxrAktwE;m!FA1C zFH5aMrozBQ6E4aoeg|fH6@JjTt7ToioT+Uc?}mdtRu=d{qgXr`X{fQUx(}07+Xo9BTDUqs7Z)-pojKHs>a_{BpNyUE)9Y{agOhA< z5=yKi6U>}}SiUA;|BZ13;a z*wy-1`}=7I({0)j2`JgL2(hVimFOm*%+UFqNXx5MG+xE-od1!%u-(})t0$+SdG9Nq z$oq@R1S(Anxg%S^I1V6JThwZkLN>y--(ej#?0>cRPR1A%R?O_-2dIB0bXw53%=xVR z%RjBYOof17_h*=fTB}7mi(E0y8fSD-Ck7>#H0%6y0~xD*`?P_*nXRS%f0c11jk5oC z;lNuMe8~R0H2Nv1XC&Yfnk-f@1%^rkMoF&L;>>8FZyt+xgTGjIWFmM z;^kEYbrna7uMkShNnke7rm0cTLa>E7CxHX_6<$1TBt#PLGg=2k=fSAN`6mi{QLzR% zbvx+DBm(t1ScDa%X)~eHn?~>PEYN(zzaRu)+Oa6?EgBj5qbZvN0ouwYIRxX%R#&=EKQAQ>Nn7nO(ZY(28{A)-oc3fDL)Jnm>=?u8|}39!vJ!-m2rOT z08$ZWw_#PFA9&egbrbv9W+<_~`lltTsMj6*;8+~apUy8@H9a^}`ob|$`0_o1;|d*) zfm}uiT6{utq3J8`iEL{2E8=+*&XnEz)=4bgb1@$3^~v>T%HSjE-sT>^p9L7EQDVBW zD6c@Th}gPV*XT{C$g8c4%bKSog+P z1>djZxdKYyqKrStt@ppQuVO`0-sWKo{{=)jvgO%r7o&EnWknX zw6W=610fhNR%guffQJx!p$hG7Ziit%&}Gf%z3Ojo)x*T6G#Y( zV0y)TPiWM{bGRihBI%LYhNeC>S{diR`7Z{$lyNlCTvM{9-YQ-TSk|GWfYygUQpEut zPaKp}0{i4JWUQU`L zzjbylHgbs-$12}yDyLHkOQmXU^t$E6bES_1*@v1Fnl6LmwZgfC)8f`uJ5EG^it>EM zh07H^KwP2*q(8p;0wkrG}Ur1k5B=(9pMUN5`zA}ZwzUn?ypl?i8EXDt1KwTa?i$KONyV{qfL%vqln}uGtmFj_T1}WYLDW?O6}-smSK;%e~Y9etee4Slw@Yu z?V)s791Vhm$Gzg<`cK(tE%|e(;_94!{xPs7h_4Y6DVD(`2rjv09vLW(jrF-CFHiCQG zCc$L<&;+S3)p%U&e{!sRF;7{xxJOKCvQP(Uk8tbGKvax!dg5 zh+BQvjZv5DhdXHrOH(NcOXKyXjTq$uwcXJT?9T!)?f?F>rIEl(z^>LeRXgeKpLLE<-@}=yPcR#@$>pUYX zR4Ng5IEhN+wIsG?7M`tr3Re(M(-2707NPzuOsVeKQBWLX8Yda8#9pFpVp7z9%%&3? zH~*ntD7#GfZO-^Z9pN?Mk$(~^H^K5(<}|Oq<5PXRxL^M(bNj3GlUIZrwBP#KGNRrO z=%dojUNK=ULio(P(Z(C=MjkoH7f$w*1(KJfsFPuu$FyD~Kh6@pH^4Q9iJfe% z<`~rZwYJ@SIRC{kmv@@?)u8Te$T_51Mop?(J|Y1#0g$q49ge7BH|a==G|z!`g#cv1 zdDek}Ma~@8A?@gw_0}C@U|H+F-Z2p`Ua~5gtaiu|P1i49S4(;)KS!ZvkU3*{v8OMS zYlOkdPqt&!g6S4_ymwp|1rCK4Zz};9%;#WHK6m)c(0Oi|<3+4n;Pe@XOl8L%p3R3; z%~1Xc|6#@*fB zTHM{exVr>*Dee|LSn<;0&_Z#C;$AGc7k4QZ+-~;n-rb#VzL~tg^3G%?KhB)zd5(~K z+o~Tyi&SX~8vBDZT7ON4^BkO5QfWrb??*7~Q7*$Lz!c#0QgNY5!QsG50RA8a@8+SP zAT7hG;!;HM?u9FUY6jcGOYPW4{zi{wt!^ z#D<9r;wVhDB$tw3w?*xRm9xnY=Y$~fKy^SsXwGT-OJ3NG`-UiI@?Fov5GUm1SM6$m zrh3Q|K>R4m$0q40@wSK(CryePDxgLUr+4~SrjiZ$ztWzd*jvOeGt{rs)UPmuZ#Q9Y zV4_bvVKg+0euk`80VoWJLdD}y0(Tw=P=iirF^8B0C6Y8$_pkv+ilnJYV$(^tHmcg* zFkGLhafUl)iC+CTj?V7T0W__qIVy_B(KY|^Ry}XZ5KRPB0Lfz zUq)83l#q29u&Wx8R1Cm>yfjlpq{Nu14RZ{vuO&Mm4WSpa&QC-8OSd=Ko73)4iBssy z7~$(f^Z3)BJOfCHAIB-OyTz>EX6H}n%q6|aA6d3RP7E^bEcL7Dtnsr5(7DKIaW@au zbMN`A1*XiOx#4BLJ=>TQX}QT*OmUk_>$3OpIBa|xEl#QEWcaCDEMHaz+t_QkQ|1DV z@)FxEDs5M1!BhK~#e-ehqQ0^UYW7Zu4iWgm9)V!h-2@G@IPH!rBU$vUDE)&xIeE4Iy}SOs&oe_76njd+VY}l`Nk6)4z`^?} z9lPoGtoapsQQAf@Zby_rdxq`YzfRG0?8R zE*&t2%e3{l{_%|k^(?%_KPXqChCb)h#MGyY^cr_2h4(|8;?=+Z1uMBu3X+Pi>EgR* zGOyEF6dFa)SU0m!IctmQx%;3ZXjfhh=^e*c_S+vA;%h0lTiDudWZFt(W@lBDR~i>d zEq5GPZ6DD%vw@;%_i-DCr8-}p0-(l5&~jX6z_P(9Lr zc(nHUc+W85qqKpu#a-2oZtr}zt{<)1&6J_#GkO-^f%vI4L~b0Z^~gDq8S=2>d5h&f z_vHr@WFkEsniG~8c%9oE82BfU-KfKSJiBV)dgvEqVoA`ky?v>>6Wp=n>wQ=8%gdC~ zEZw+6jCzRZS7-8%nE5M^a(41pU-Qi*$x}tbYLbBUD?y5Mlgu*i1pt72lvVI&Fs0!X(fa-w z@Y-kqsvBgukk?a-*6<0VMF1`|WkTOi5^9cM8-;6v-S~MJX=(Y2I0`QZ+Z*l+&G5j) zIhyJm5W)7-q``FtVHqZJcPA=*BHgvpQVcWf;pUL0`({h79})iX0M5G@8)C0kr)}L0 z`V-)H^q?39QM|+Gm3&N>tQX;;4yU3?N-(BNsHi|7)W0CAmL;(QvFRe_E0{aEt##~quLH&PpHsmF(M&V11h zZpi~^@nEHA3PH}uN&sjmM@lN3!Wm=FS^`F+#)$a-C$VnN zZfHLiVcjcvl0HlHfW!vBDm)Ecc7M>s_8%699?-UpN_b_cVFbsH6NC0X_yrYwzVG&! zG@VI#7V~TMGZgJ*Ja3Pk#)9R7JDEm273-z6l@c>hFn0K!tsyDJb@A%fBH8v*8S49p z`Fb{%_jEk&elk+qT}<5-DBly^3D~R7hD5d29zDC8&-!h&6<&1t>TiY~f7|HrR(H4P z{^@5PXtWu)uh-?g_dVNU#@T@5XL~+?azmn|djY2%e9)E?dSgFmZHMn`88J}2tT>_pzygjZt zlCDr*B)_#|cS6Y0oa2k$EVaSxyz=7!+EXRLrS2aCGi%z6A9S31sMo!Zp8JecnVCRP zeudZs`Xm%Tl8m|D-9rAMryS2=hwAx-oXvH-G2PH@`2YI%vdj!=j}4Qx2-+bJT<#pS zFzb{n2!fn;JnIx_@hlY@&bl;sL!11J^|GCG=oX5-cY|%o4t_Ns2R4)bS>T-gMlMQq`D0L*R9P+TsPzv z>+ky(e#bMuh1TD1qJ-mSoEnx{PEKUuumR1r3*>lf2$9Qio$ z_K}tU(Md1xr5xwTv3xj(-GyH}4&*&$XD1XK^fE-wi?U zbK21O#ExuClVcN!pWVqE=+{po-9`U?P%XNiMg10SdeFKtm6$0KC6=fet_%2+$Mbce zPRYxpM#to@7{9Gu1;2Huf4>@9wk-i0)NVS|F|!xtNZ!6ktU7v;Xk>6{igNU=F`$b6 zT-4-$4|la`|0Qp%Q=}O5`fuw62P{{c;`e?Sl8adHICy-NfH8;Df9=k_y+MJd(f;bD z!j`cC9RaDxoiIKy+|gT8Mn_sm)7ug-@lR6Jg@iPyG{`yd=CI8V$R2Rl+g4~f{n13k zx?3b}C8bhAg)}rNcj0XoZ`auuMwi0qyx!8tmbkVP$d?FBGRQQv(>N$7oh6cN^-8eT zQmhBtg+yNE?5D#N6;T_Y$FoMT@shr&aYWQ1xS%y0Gko*`hVeinU*ZV=FG^d4?M8*p zkF&N3QdV)c(<9_l*)5WO5gv{kDQbIm0bX8fv*=v>R~TZW#B^qj)my-1-5`8mLzWcp zB8Z00FjZJ7&K$Z9_q9y+B*7n56d$WMw8rLQrYSISfAR<{&VvthqlO)KIJ{HZegn8x zpjW~9!yZ8e)KcI+QSCckFpRVKp&L4l>`!orcNx~}j9>@M({hg~ug1SCs!O(?;Na;3 zXK&e`0}n_4!pQ=Q1#L}vC5NG)3%|~dyhtSNUV}c4gM62YO*J9=>E>~>^SUGSaNiFy zXRx`DVjgB78SsqxdNjENF>&v#r0#x8P_}5f9$4Z$MXt4&IJ5{-+YHmOeTR!?ctLl@6NVs;2g_ zr2?vj_V!pfoGm|^zV4WbnN_K3_sK_RHKLzaCQCDQn?IC#e>rJHBWf`+n(JjS>*}QG z@Xc2`*S5me8Mf@_L>~x}BW$8m+g@ISeqxE!)Cc77r(-dZ_!@p+g8K1-n?CoM`w(+gsX%RR? z4W7K^m-{3U6lyA%vyz>Z56Re%&1)44^5+Lql8(Gm?oVfI@dE=blk&-OW|u@_AfsO- z#Ak%d8R4C87k(gngMU!zt#yiKsDhypHI0XhdO?-C=j;aZ%F`2*_GMKQwX@nO0YsVQ zo!b0F4PS!;lAJ1E(H`gpa^Uf>6bUhq_OW4}I?)~?uNM)Z`;`SoeuYX`&D603JSh24 zOCqi9(3S|(>U!tz}8xENi3RWJ&z}VGEvaF&NLf`}rH*xeF@KrqaH+ z=1#g(cl_*csv~<48)Vt8|5Y;1B52DIlYOJAHf&p2{C1)2sehzkI;u5Hzu@`7wd3$E z<#a>z-@=c7T^1IhM~Q*Z34Hb?ru~yY-WVb|0c#?wDXv~`9vAeIn91z0xMoeitng7b zVR3Lz@Hx|xg4ne1d-w)1!1I!1QNKIrMxI#L_NLaBpCTN~1QXz1kq8Akf z3D{pvblM>Kek0k+mC|?y^?6lwz22?ektxLtQ7w9fa}>A0m4@pRbDGcpN2iaOF06@^ zWH`Ytta-ThQG`69W?K6;-uOc}U)4B_V>lNKy;RE8^oq3fK^*G`oVdHa2;*L!VMZ=w zw|Kx~GbTpMa(2xB$!fGN{{7+~}a^tYqb5sV;6T)ZM{kj&YmDF&7 z+u|CA_s$zYDm5X^Hw*}Cxa-7+{Nc3~8>W-@$A*cRC=gGnIZ_VsK9CR*5>gVj1b0dH zN*~BleINDOgcV^{m$Xlc&Br=wzs4q*fd94}>=+Ntdbk}}+MEGz@W6LIhrHgkPWEmF z7)ZV@{(ibzb3aye-|O2**$9@G47g!@eMn+`Iv4D=oxM0xtPRnS4BiiVdQ;h)gSLsZ zbl;z}-o7q%SNm-St6X%ywP2kK6^5AHog8h@uhs|rzB^m3HVg7~nwyW)Pr)|M8R>h= z)GO0xu1&KGH)p9?jSE1DH+`#Wl^g4rwxbVSh<45ZJ!ZxsxJqF}ei|$`It|Q=KXkE7 zv=OQ@q_Lr|!TZCnO_^C+s=&`!wpcB+#cnWaQSHEG8D&sv6#$c?tN=pLC1lf6X6(@W z)$x%-LvI+gS)8(Y<%kYcFmTg9?9IsMd1U-vLS|Mk?<_z$eYr;@-W4oo5n`ugVIfk? z85&aY?-kP~+|jbqagb%=vwQA$d}ktA9_03zBk_6#HcFju z4D1>fIGet#WIrJ_uH7h7J0V>!E;BoAE_E)+KQpWS@w9Z5yX|8v(5*hsymsXF%y{`RWZ^n50FmC%`XItgSvgvqxwg3YQ)Zd%-HTk9 zQTxZS5F!q!wQTuWfmNeG0OO3jG=;lhVCB=+{T(o5Ow7Tt*PC#%{_ZtvV|{>`m&Wq z1?~5Z#@EZ*>|wzbs|BWMekEoN#^c%Qjw`d=>?V zqfD;GT}CELRSUy%AdQ{k~n!pTyDdTuKM4@{F?Y zd%p)L#)-MoYZ3#@wG#fzFw*|cT?i$#nVD&3yR0jWML&3gGD-u`4>hh#qtf^^(XSBbT}OhHFB+~@FnVUOf;1TDhYB9w48@+ zwk`{PHZ5#Bn)qzRr_{asv7CLNnMeug8=N=5D7K6WC)F8-I_?e>w zgetX14TFt>#2^;>(uQc>2AL(|LR>G#o>GRFo1r=t7=~9ZCSG(mobgZ^#Pg2 ztB=6}8=+Lvl5W=uFiJs!yd2j|ZHW;#nv_o%mQ`T*PH4lqwkV#_(FLVQ;DEbS9XAp%S1icM^{q41D1RjE zYKw`V@llRwsKH-&PKs;2pi-#=b#d>){I%yPk?FqAPfSB*L}uZM|HL}Q3Q&3u)yI8U z2paBT{Ex=O$0RN74?OEab3c6=*VWRlEa-l0dE1)wyB!zYoVf^lHhEfk&+cjspE@~O z^56aUPXV+=@IiBRmZ(zq1JzE9a}j$}83FdcjV!VzO$t1Q!M}fHWg>r{dL6DDUv|Z= z)mngso&Wlb2Q)4=+TFFCXE%qv*fVXjT&IlC-aAlSCl8fu4Wi;^6_$=m;H6Z_qK+0J zZgQUp@eGX@gzm9?!A7SPNd|r&dI*_Qerd4d%$hPzu2xyHUc1&?uJgwg7@Qhd4VbIv zzEkmr_=YD{xUtUTyF&HIz>;5*ofKjK`-7_WODFq9q{vo}hNAHU;oiBH%NAKGxosyq<$~jFU{&*2vzf44vy#KKRLm(4CxxdD%)t8!W z3L;1es!bqE+MRP%7l4a1Hm~!)i2LxavfrQK>sximJ9)R*L0H&|Hd}IX$ZEqmb)+Qt z{P5g>bQ~&@Oq0L8@bKyK6$$)6B0Sz_ znXK%+{e|tZJr=@O&=u*G?OuE`FHE3k-n){BBl*p}Z=r(n+xfSQagzzmYJi&!5-)v7 z4yn_?yp)QPq7w1&f&Mgi;l9mjP-R6$wdtpR?jS3@=N_DQUD|JC2Nh*m#!eMwi;_A{ zIX@QP36+1!3l)A`@Ho!ae#Lp$;Hqt4QMnrDy~#;FEat_&`Ghhe^a1sjp{>M5L{CUc zoRR|&k>O;|egby~OMiCnFV!g09mmt~UOctCgAiS(tr0iT=Z zt;`TK5tJv!Kj#*t#uM2Ceb!Hm&CP2J!S!mv2P^(;2F5|SF!f=OMzb@?K7!{)*EIpe zruxu+LE}GHk(kD`c&ZKN2ek7$ZC(>?0z&03#MOUM_)y?)mp{unP8)Fy|_QTycfb>ne9 z7s=Oe^mnme7K0Fc&hT#_;AIN-|# zvdYr~4_N;$)ysDxF*8q<&at<(g;zo6Mcl&O%OolH3>rvjKueDGe^vY`@*1V!~HiI#_Vn#L3q zs?(efD%&tK(2H}x$A$`nELzV78&*{616Gh+OdGI%9oF_%wzJmT4w+V2JYgP8eT%H2 ze95>ug+MSY0glKj> zd(_{A|4J%RvW6!&(J>???bY6du`>?jTAYqfOO0>A0^RypI+VhDp_&6a>T&p#!s$J2?o3Z&XsUZBKQ77uf>l<0o&Y-ICzg0EH~(& zXK#-3DWco3E)-eW5jqwtw2e?fgxVfl6xJIU?w-5pg;xDxaQ`TRKGIViH&=LdQAI=a zT#o$?sj>8cR2!YTtVR`T2(2tFJ-fr#xc2E8y)9gKoqa}(m?s4;0ltWcd~WY%OiQP2 z6m)0goUcZ`ql1R^%O#olMWLrFu}EK$xMqn0-h|M#EJjEISD6wZK5|_hR_Bh1Pi;t< z=Mzl=bCE4s-Jhds>ZAEFK=La{i(I^QI&Ak1sl?_OMb!lvD*QPcvvGZaRi&tbNGd07{r+!Q%QDvfFIbaOgjQAkKUn*n70@}E z)f=uKAkhu{QmX1Uwtwp=Ec_@gG&%f#lqrt$7(-@OleiLY@e%69veak> zI}ACb@o9!P^Qxl&%OM3-yN&RohUS~9^1P6+<%ffL>?^rr`;p{lZ@%0eUEIQpO2J*QSe z`}w92*^&3}jATTO>G1YuI9o?Pg@1xkdQcWpL}39??HXdOfyKU2FAn+i-wyi6c%B`N zdD<8?HPG{w=vH5#JTUaqbCvi|NmI?uG18>3*)e*Q6x_>Jb);n=|_F<=jxxY|)F^ zq_Q#cg2|@iW8Wjv3X(?ZG?=!( z*O7RKy;?V2+!CFwi^_~IBX!!yM0gE3|& zgmUm@rFWoOe1lww0ym-r7hgcSzG;`ei90QwOT?RE7&vHY>Oo*tOpi-S6&*KCA{VQn z@Am6E*AqG@~W^)c#>geUu>OFZcV8bUagw#Wi1r9AM^Y(4?$Q*U6Z;!m*Otvb8nZLA(Aw(2!UnFJ`jm&CZ^W-W;wo1P zV=(DFo>!@IT_xi|(wfVV&?{$IOaPRIWf{K*U0r}po9Cb2{|C8H{ugrDA2i?I>u{~)Vs#3x~ z^(#xvfd%T+D3~Sbq~>5?-XY3z(z;VcO{O;Q4%;K`){;3{M1d5N$%vH$LOV=@zBx;b3*9B{ zPS)F-tb`4#uu8Q=x!RcI=I>v3S&B^Yzf!Oc^J33=Y~*I2r*UaSinXX2?`Yv2&A4I) z#aL2pV}iH7aB;rxY3Y6wizx=uv#2I30%ko47^v{KN1`QRhyD~_mon^8Nk&Yx`R`M7 z>8JY1Y1#GD+I$m=gW!Aii^rUmcExSp!27yyM(%G;=&;=gaQ-cZ>6%pO9{Nf+UhlJu z6nwMbQf1zP#(5u#dk`~R*V+X96;K=$*#L<`T0O8-1wS(N_)qgf45D6PV$lH;)4t2;uKRc?j58u+1i z5Ui-GA4_%geupEM{7#_L{eXlo`Ak8LoC0jM#}-=l@7w5?ZU^<6ju3V7^=}NDb*gUX z@SLisK3ic)yav*Cn>Qid7`XJEm6>o~{jx>*{=z>zWg3@?S^&_UXC~ouf$Q+5K=FH4 zzx2J6LZ)Vh1lQA>hurvdin0(yDXPgFJ>-(y=RR!b+zG>#Fj>8Qy|}VHvjgSTqtFjX z%3BU%fbvAJ(Y~%58m)4FlvTje%ZB9S8nGNgNJ%fVEKBrN#4%-a97qRDClYJo zIhrt<3mpql*+b5uUzlIglvex=WTGf4Y;lN99<_I5I3c_>F>2|%=|ZCOaKPzTl&9x$ zVe6M2p%t^KYM}HDUSvVoS7VQX)-v=sM2zb*_}q^Ds&Ywr(ZH9$J$_S#@iN6W|Lq94JDx=6nQ4Dg;;FyG zfAe~)O?oGPOWo|72n9AElr0=i2mcd6OFY%G2%@BXu>fYq<4<6yS~?$LslapFJ^9M$ za|t#8%i^OOqH~FVUs5RHbK4_)opsU@=F~Vk_InJYd#jKU;-An_VTXcPL1I`KQ4JK; zER-;B=AU}#pu7iFw~UPARlAaU=NYO6r5!$^>VQm_cR!3Pa4jdJ_H z@9JSlkhdxg2)?gUjv|bVCpoJ$PW3rTGn5;h?=ccIjhb`^w|}1d$bN*<=g_4{BTtgW z*8N--O(M^wSYsI&66 zq?qV9QYwx2QHuJqaHUv+wyUy3(!JP=7-5OVZGNM!En~Y~*;=45p&p|2`EMhwvClQS z8AsHsA(*hKxRDyo55K~DZ3Ih5g1Ow9%{F^pJ!`?cr{ znm{%dLL3B3Z~&sig!8RVT$_3`3hZR=-4!C?0=(|}E`%r-`qocg>(GhQqov?x!g~VD zH=%*sSSM zHeh1xe%*euZ#P{tUHYcd67Be?KE0D-Eid`Zxk=a}+ienTCp5s&nND-D*(Zhy@wcNA z)-v+MO1S=_rJs@9-w6rhm`GpLTwNs_)ewof&cJ6;Pf!d!(IWW4@B#}_FJyUS_@u2( zP?%ldfw!WVLVL02$*9q-RFE#0qnPT4<2Zs%%TBBQfW15IE_$_gzgF)(CF5e+f|Qq4 zJ6ul4TJJjPsh!vb@L$3MBx8?8kLd20n$Ljnl4$NT zwdNVoUQ~Xg*i^5FptDEY#0OZ^C<|zRjlciL@WDS5XueDe9xaXG_3=m`3?PKhvZxl8 zRhE4@j)%epW9y$2lAsClL*P@ z>?kfS522Vu>ST|Z@*|A{7ESjTW)&_r8>FW$Dxd^4SnBs1ebM$2EG9CmL(cKQ{17GC z)6}$p3p%E&n=OA-Oi_F)EguN8$kh%(4Ikd&$Wc}{-M;=f;gJ|@JS;=kRh}B7R0}`~ zQS%zYo9ds|8YQ(0oZ?#W!L4Cs!w|D{Wg6~ZMLl2w2A5k^nYf$p>uZubs~E1W_O3S& z9(g8mL{Qn5x?@{d%n|o44iOnUAE|8Ak8K+*^aSwj7pLROp6lo=XD?S=#>>w|FZ6 z`Nr=C41g>IQSHj@SVH1vdH&PBFV;}~ z&7yqUpBKA`Y9uWnH$OB|7S&KV|8ocqh@11&I&^XJb8d2Ids5aHu9Sei7UPBLX1piv z6a;%<=o#^n@Tql>A@wHt;(-5feKp2z4*sa;EB?m@O4CEODBH#!RZdvi!><= z&xe?C-WP_^l6MPz|3wX{d|*IJODEsL4k<7|Cg2b1PgNBe&oNJe(gG>K7%Jl8K2uZV z@BTdo`N#P9u@(Qvc;-xU_ZuDg;7?)==_xd#AFx*FEYv^I&1x|0T>g7qZhjSHd$mIq zV6%wAWX-aA9Sd0Q^raH0SqW!E&$7Cmy)}ePe#UJjog3DWb+0e1p2V;$0l?<_96H%0 zB~$%F@n}{I5;UQBzZE^(XoIV7>=}%sjoSM6NBl392Vbj{Mu7l|M}16e7gZI;E1+^8 zQ3sQA*{L-;9e`ZqTioe;*>Da#9KwEJ6@T7&ZAJR9XuxaF(MzHgHgQysl87?I+O;7a zbiq;AS{ECYOTS*d*1y6dmGPJA@9KR&@I!&+H3WQlywu3e?91I9ZnFeH25lEn(+AEP%4vK9Y2og2Ie4%<_1w|sUtEzO>FX=M?JXXjj>7j{l{&s(5qwV=b%!!;J$*_2Zs{_9Dxn9-0jR#(VH;&(vAAX>1{|~Ue^)dJ#ZoE|^?*!~*^7f`v4$E3-ldMx{_U#QsQ z^v<|N_mft)Xn`bxN*b4zxD|j`>8ZkAJ>15w@3zTMN_SMkPf>t+kJ5p%?!eEqjo*i} zrc|d$GK$VxSy@SN%GWQLKx}~%JTsPbi+?l|2=a*OjSV#th#&?~a8}ZQ=rwoc@tY_Z z*yuH(yQ2^aoxAkcbbS-HSo?e2HswSyH|BCeI`%gdWPE)50#lfx4km^wn*fCTs=Uh- zYguOrH^Oos+6YEi+ULP~>mFf!gaBZ6XI0cO3b(KuFa@C)7*9bBCvHUi3=Y`J@kmB# z7HXkDzl#TdQ$#&kwiDKOVIH?Mk7-n$Lfu`KToJ6{eypj(5;lkMVlUyJGLWQSCWpd_ z%J4xSu}Ged%J39Nlwp)9l)rmV`~D4+Y{L0Q^S>qxrM0Zgz$yYAaH=bA@+RF{G zc5{;*kL>f7u@*;KW^AdlCIwzaQxzo#SXy!czP?xqGg<-490@l%Z|D;`EwhQfVy|zn z?<5C~;;`_>#!xb*uArwt_G$KuR!$~xrzxF9N#f1I(%jPtEkRpu;LDd(=8OWF?^5O` z++FujTujBWO%`2o-uMlh z{l&8;EfNte*axz1*KjDQV8f`fo0{*Vnp;SrjaaB9A`j0jHMPHxJI~Cv0dCkDL4G-8 zCM>N{fr+SjR00$|?nZIN5DQPJ9P4(0SxYC7V6tD_q5zcjRftcIy7xHdl?CVg*Tk5j zyxWJb&fuNkT}HkIzHM(ac&ASZnmVSDbleZ|SI-`F|582DJ+2G=B{CvQ>6z0q^J6DK zrh9w)#Xn0mwE*g{XmjX;Bt-Pg{KzX66{C|%eeqGT9^UR0-6p?DH*3t2E(AIHY9*@% zIX7zwC5cY2=8~Hqj)~nw^ONLxnE^2*QODK_mVMdy^^SxiPP9Z}yoC4z$beDuzgGu0 z8xPBi#-muc8?X<{!>DOi^*wGsBU&f;E@LW?o)U%s)s{rRb#(a4r_2ug>OW`he@1Iw znvn|E6m{K3YhIX*=_$wR9P-!kH5RE`T8u8Kp)$pQY+JFs1d`R^1xx~8#7zO#RtU(f zqHV%~z5Sy|OfmX(_1@vR6@(ymRZAN;40wE6Ug+oOYp%@rC<572%rw4}IKGBKz0};C zKx8tM*+tM{x=t=OLgdUuWSUla7r7(i^D!qN=iB>>u(h3HnlJP?3Apr8+`)1<{j$Y` zr=4-zCAegGz`AKE#1nZ1EQ4?=Gvm{lPwu7=!=ft^a$zlphH2d)N@9M*-4bSN?RgtH ze!qqyT58r>_}DB_>EZYOz6aC!?;Xh}l{XGzK8S}?f2Gu3jR-Oq zw^|3vl>Sr?+^*ewyseXpb^8#*L)COaZj{6~3R0hroLskHoUNJbTcS5-vFxm>Fx0#O zb`CYBR5FD>!o@Q0^&&2{ao6koAM#U1y#DSDVXf1B(v+`L@Q^EHfFnO{j+aK0RUaE76&0?JjaRoc z#q0)nK}R#zo0&?GW%53b1nxg5b`@XzzUbDWAp?-D^}T%f@Bxj&S~RyH#PU72z!kb! z`$?x{O%4Tx>9*JGET45Il{Uq3;bg)hhSNPmPnR46WKG@AD@W z5ecueHY}8#Ju*9rXR!CTpz>|rXNBn@?w#d2s;m+JyWC?V=C%GNpeqp2G+MHdhhPh| zf#9#tWQIBpDRL>a4f_n=DP0a-?{^&XF0mK1`>v=b^Pkc(*bAAJ)92VcFPk3#NOqU8 zvnD;Q16x%3rOK^MRybPZBgM!FwD9(DmGB_-lNe#;mifu+-6OKM%}ts#<~d^%su|_2 zUx~Bh6$r|hXe870{h2j0zEllnmj5VWU{^yth*xKzmbKIFoaVM+WTfF`#5MY(=;{4V zb+%Sd&PrU>Urv};A9`$D6>k=q^ec0Jn@@*Z_Ds^(( z?HrYt(tNp>+^xFE*#W_iQ*xh3&y12=naqwZNfde(-*!91upnm*CcEYqn50gj%(L6t z`e$)D-jcN3ZO0h;w+-#LK<%K0^C4jETBAN-h|eWQ6x$@brZ=IM*lLCty$*6}SY=d) zk!O_+*gh-(Y-Hotxy&#dc6gu>apoikH1_m%8d)T^a134tc-6bDC{)FnMK8-I*4rG* zu$gqiuoAHi4iB+jl^mUdS@i)UU(1$%`;hupS%jB}wgB$S7nXm!65hF(L|!Zg$N!bA z?tKe!zIxt}Uv6~A!b@h8U+q&NgZO?kW(<8eb&(0#&0ypG|u1O|I zd|bghC^WKj6yY=aX+0J)XpxrLOr@wUw_`Z0$v~BtSemYqn$dv7{6%ovf2UQ*_soQ1 zr3W#{w`Tb5Vub$Rp+;JpGpzP~jr{e7nox%q`<<&r@@5NLZ<_0Az5DLxGvh{_o|-o# zQGIBxBe7av132>XwhbGXln(*y_Ya2J@2Y?8x2(wkPKR-MUF)qT#~2qEzYF1ZMy4>x zr3yfEpfuhON5;f7%}-d9Ps`WzwtVu7{pG7d^-fZ27G3`ICmndC4zg+dnta3BPN@O8 z5pA)xgzO5zjj%8l2`T}+ftVB-Lk9w@{$W~ge}ewVl8l>ce>Zboo4AMAc>UmrI23FJ zZyN#y#fib3QKKCi3h_ zs?K`km&m|9!h*i-HZk2LQ+ciJ54w6yh5HafT?4_Q(o&=zs-Gh>r6S*cdmtaG7a+UA z*WL%<6Iq>KpUIGmI~$&^_8Nn!1em5g>UNBhvFcj5iJeWU4-|;FW)2tk!@lRARn~8168TL>oTjH)%o8qYac&GJ9@(00jyiwem`U&W3 z37f+XL)s}J`!8N>IoUpqV#$Q#G*zXHwC`9HLWLR1sUzJsHa09-kpvNpMU>lAty{BX zsUgfwB|g-1_@6(6P~}&clcN!0t8^ljC3wH#ByLkM4|`%l)ffdXph~IbwK0 zuJ$B1<1G#5E~&35+`*ON-?+rh)QZxy%#}PH2>u2uqeic zE}pgP?JeN$&J#!aWEJaPV_lbT*TBndo{XUuU8s`m=JAv&OMr9xn>zn~HkYT*9|S_` zDah?OhE^}54N1j_(UB&58*nYGZjKlY@x;g*V?$#!By%DisX+t9m*8k}V8sPypI}7a zgVQL=#FGPx-5ljLQF-?}T6qXWM1mATbO6K}C{5WIKD$hNVETx_J3x2k=)q8)6gQkv z#GO!%mC`$pTf*hDrwPKQVA)Zmv+5PiAtg!pGq5?bM_UUxAH;nK4d&7h6T#CNQ0N`_ zV^KwqPI8pjKdnhUydyuONt3|=@xjbU6l&AUvfs_kC1Y(xAtyhUUXrR37q7qb=9l{x zw=|=>NE`7zchtVn6}ULgX$+p>C8&unmzdzgv@9Ah@vPnk>_$spbVe5f-02JnIjn-XnUY~E7Z0IfWK07-t(VJW>;yT`k(cTvU(p8=N}l%H&dxgJ90F;z z-aVx>K@T_?WMu27!Q%%@O@xNAi>+tzeWfWUX)SNume5g2_Ry{Il$S8#|0Hi= z_Id08bE!3bn#0YO?{E-?33?Zr^)J&&#RUKmJpzqOYF*M*us-1&4h{}MU1-eAe&a+5 z8X-$=@?&X!Z?xpoBsV8J1v()B8XjjM@7t4zA7$g?>IR)<*SmIJHIo6uN^Ir|`E z2R|)cEV{5r+oK&i01U#P5Jl@Erz3*T-(B6-4{5 zjWDFbWkLi6ptfDd<&aCEmPG0zSMnCi-7!}~{NM7RcLlcZt!RloMpYAihXo;#wf4c$ zD>~hM6Y&<7PY=q=ElflJ_xpiwT2WV%ZGPO>f8RVBZep^^`7torES;VMnY(hNQ100RSzgmg%EODLdpH%K=_hm_QS zv?8g1baxIZASsP>cZ1|J|Gm%I=e#)2%X$5~W?gH2*ZsMdS)qf*A*XQ>ToM%A1tI7> zp+APgn)-ba{8_)D^!!vBIZ{sCn>{uxTeV;Dd%ed4hPt;P$L zAAwO%&g|zf>#Q(p;$|hfF77@cDv>UC?5CVJ2%#zNDGzqV2yu=GmCl@t+yFN0SJ^;9`wRY;{B<-uG|fjqaAw#+Y44sJLx9Mo=edM9G$VCLa^x91AE4a;}YV7#=8G3N+HX($Xki$4g~lN+nH3EnY8jRP@g^YH_~FFXhTcCf|b8 z2E0yIq%qp7j21;y)D?CVBqxF8r*Llgt}Wv$x>qq`^^rEGRdI_rDg*uXys_He{QUgN zw|RLCy%X^#3FI&m<~N$0e@wG=xfY~v6l25+m}`@!VWrs*mK}4E0e4sQ{QO$)p=B4C z_*CDXNua8i+aNSh#YV8U_OFxASIs^5L)24q0ayGNapt*@n5-e#$pNyhP=tR6EV+gzsmr#F~FK^md?LrQcr@ zu@-H-(#2XB5%|eJ)SMA{$c+9i`+eic?siM({n?*Smwd68z#AU?y8)4#_-Z3J(J~Lf zv2C29QjX%-wJJi4<2B%%7g@KmyilhoKjI9qslh2k&d_(XtTW~G29=VZ0~nd|*@cn9 z;9Z8-Hj_&s(&!PEQo!$UnQ4||hJyPVOV@Tm)}$Mx?JH1OHyu*e zRN`iw)s`Z>$T7dt)*f)OIonWW`j$w7FuwEXP*h#r7~Z;vTO<|$k-SfhorqXq5%DA; ziz5nLxnNuwCR;gpz1s2kjDi;B*Y#1}(O$sICI8rh1^Ad7VIxZ*`-sFdDyJox^+Qo1 zwyaUW)KV+_GxfE)=VAO>MavUt%9}Q4PZ@X5*%-0wCrHNDS(6ug&hYeujnGx$x2N(( zSz~~~4(A>ORbI!5{%P&??`V%rL0ae?!YDb$W2!+na?CU5qtx3QTrP2`@m|FNQ9s-| zZ}}w^K@I2`nMqq*H8r8S4;BkBfVJrslp-j1i+im>f2I??ZMRBp(g?lvqQ;*&%Db8f z(98}B8?1q=bBgFMdeDT&Q6vWK;hdFl=C@uE5c9o(mQ@1&TH%8pyXgGMDMNO1E7mq? z4|@rN2`}O@%`7c3aQWOfLvc4143}a{7US*NEoWIdoW5`3m)(wy)dUxmV|ZMY=2X~o zY)#1w*HEhR_bi@m89I`r+tw}l+viz*)7{>U;#WC6!-L}cF}AgR=UDP-gDeGXTj5dP z(@H$r63KjE0D?guqgGtxA~DQVcerD5spA2O^dJcEWBNb1*&9t#5}7z1(=67p7=paI zCC%7-AynB&HAL00`z)nNT-fmBz(BdQ^pQ^w4J#SfH&96{<|$m7jEZ^`%G{z2Sa@{j zB!0V}sHGkmT}+-S?vBN?n%y=18#h(qO(lQ*hc9)^i-!Sb&PSN`?`*~?baV}bSkpf0 z>dzu(XGujwM4m9V>aw!`SDn%>K|cGJ*=Q73zKMq1|27F%=}6v-yjc$S32ZMTmqzzV zuBec__t)=QF!{I%lo?agAtM;$>SioT`fHi4ihPjP97-6Af1tBW=#(bgI?dPxyiJei z>=w=nlSUUqmq%Ad_x3Nq0C9|B=h#*$!W4yMvE_66Rrs)5k#GL1$bTG6;h6$kV{5Be zZ*zRAOPI+bg9=PBMlj2wf9N?&=u1@Yt@Z5I`_P;?n_uGoH|jrRogPxAz0d>1-odq< zYOmJa0|OtE7Hl%&59wW?$={}y98cqZRlm?buQDqAKpx4SH0|y{olDp4qitegk&n9H zXqDDkQCg}R;t>{88k195UHvxXGrE6i+M$*387hJP-6@_-sAxRo4k02$SlbHiWVmOr zObLuoIqBtgdcOrD82}o)((sCNEMu=DLk`QCYN6s0KkItyIxq0n!9$*%f0+kTI^+Jn zw^CFuuuEZnm=J*nM*MU^@Bw~dU+Ho#{JN?#j3Bum9~G)k*@urF;65BcrJpY-7WLOx z|6x}w*Sd<_JQvRys;@F3=B{RMc1Wrv|F&au_j~~QJ0JU;ot-_4C%sVjuNeM0u|`&E z@LufmUbU3(*_xVJ(m^=N?UKnRMNvh&y-1gCTDDyh#Q+&V0@kqd6 zT%Cb{Bhtk7x$a9P>?dZaUM--6!aru}yra8V-k>tD7ui>}oVxxSy(a z+Mqg;Bu@V(z+}4Oeo1;>?D%494!otmwmIn;oRJDpeHm-|%?uk&gNe%__vMS%ud4_e zIoU~Z8y+8wds>bOI&%fPYScYAAM-Rwvw)s{pWTa=Lta@LxB84)$%yZa=nSI^uZ-fH z98(KMwj@3%Xl8IRLO3Vaj|2k|K#XmdB8$AOf)Mik%U;kJz00v8%)D0D0<;cO06Y6I zNyGf2+>=R;QNSrNDMs|eb+%16E1sD&E z)wtk0o~(@3_9H$4#=45Kbx{qa8o+j|Ri{V!2QHarT0JP$ItSb z$lkvw8hIuCUO{4z7gs%%5mDn#rsFfhPRy!cq|IZ;d#;hlxi-P8@#*upuW*EJ&-aXs zfuShHiBqA2zgn%TL(>-L1G`-A2ZXHe0Qb&y7DKXP#lg)Ly4Zb|u zrMgjq%b?)2?Bn?B@REw$GASAhe2aAZFSs*A^%2vRRe~XPDS}{{#T8QvfcI+9U3gYH z@GozBls`p{f|}-Dxm{CyYs5lP+cV3wMH%f~j*S^Hxyv~$7N^$miPSq5hvvvNK6Fzl zr%ANm+6nS3di7pE&3<>kg&nXS4GV+$)8&WirQkt#>+|M1-ae38bG&Q z>ajE;M0^a!vK5?5C+`>V-#9jRjr_!V6Ys<=P#KokPI7^tNt#ob`yL;kLq-1cJb84j z2YasbdwdIf(R96q?nQ)xu;j>~W~*gEz01p*cOyz0^>%zT@6vbNsLONR2q4nrX0#z` zapBa>UV9;dTy3#%iCd}r^$P(BT3!$o?E|-)CS9nkLNsI&7==w4y^~-Tonox1%Odlk zn~0dSoJEX<7%0sXg+mpyvw{@1h-r*B4ybW6?y1D$-r~qgW=3z6PTrhKiF|U~PfRpo zHlCdn@-32UjAP*}RaA1tC}!PHNHhA7w}^XV<(=iW?r1Gd=61&BQhY?!o?Z_o=nHh= zwnMWQ$HFlDydMRj3BXF<73oy(ri%FN#XaL4lG{$^0ecY@O-Aed)q456*5Q)^G92`; z_+zU6XvDw!r7#S&7|7Ls`lX;yAFIE+IK%eKpt?_o}~g#FCJ7NE=Gp-Z zk%&oNII?w)q2MHX9G{P+iz9!(Xskk~z{X!dU&>IFj{z?GX*;gai5%GMk%>VBKjMWG za;0UgUk6M;Qm~UG{=nw(;`q*lXYiF+^#mUP2Ao#BSQk)D>tx^NvKoqtr$=r^GX#yb z5X;r~^=)?J<9I0j;E3#`q%6Mx)-uEA0NlmTCh6{BCJ zFtgILDjMRFe(eNg<&}r|7QD(1$%|D@wzSG)XQsx;0K6jQS{ju+K!p0RRr(?yqYRs< z_GcV==dBhhS-r@#`<*(g|JqmipDH`(ci^yT2SSY(eQs8|L(Fr%r8Qwh7j<=}r8dv! zi_oBs(9Ok{qVL#dTlBl<`%Ktb1ZQ>ix~C?voIA!;sz7%yZ)k?Wd;q^|u#84GBbZC% zgT>so>y9N!{oz2@NFyt0)XABz=-^!n${pO8yXg=HYgKhBWn%c~kIO0|EIx&Sy#uX`Lj!(E;bS*doWx)6QA>Tel zzG82SA?ZzX-Q!gEx&&5_h)Z4ljg)~WO7Acs*qqRq_m7|k$vQ4ruY|9Ogek&JlKmPt znu)XL{UJ&m4T)ng3Z+8Gs>>zEbAGgsh4P<2i@p+i0DZKfje)J$awISfzWt4=xkPb9 zNoSIr=Ba$qfHFXI_)e2~u$+7|8I4()mOlKD!fNB?qP+574)(?5sP83LYrmGb%+C5N z)+WbvxK}Vv^XiWQ4Z%w;=lghqY9_M_zFpJJ9C&eGbMkE#?BWUsN~c)WhCrW13dZ;a zBHDkvi2cQ3YHe2DY8p@A zx(GVtXuY4XH~)p#x9{Bg;Tj9SOHnq$Vt`wwEf<@TACDf21@+(HmP5y4@Ym!HRYZSb zBN>JnNyq*ioJc<&g+uvaJU5A($s?K}v~9e*(9CX33@^}L?CnJH>0OoPbDK2!jvU}$ zAO2TLtcqrjl*uVs(mp=odwXBhHO7OZ&-jG0bU%DLBiGav%&9L2*nD;}AD^LKwVqTe zovN?o_Xy9Z$B(TmORj*oGXP`b0O_!0fa`es73mwjs75w^I{d|=eVf{Yf9*~GQczgnWXf2AJ zG|Q>~P<7}4$xTLojjn}mL@YKD8Z#C{9?Tvy?N}Pq85?|Dm>u{wn4xTaRzQEkb%&Q)f5mNK+C zrqq5LRQ384Z7&DOE|vwgvb|}$$v*};3bAg$0A8-OVGQK(g$ps!9OQ+^!w8>Ytwjp4!WfnNy%?pT_gN(54 z+k7?5Cnn;BOu7Z|#ro($R>6}Kn|w1k$et=Y<4veUs5(M4b?7DOkR?@plH(@>yBD{@ zn8~%Xep{wlZkTB&BwJb(DGL{JKi?!9c0AD$5+g5=Q5qx_;GS_5gyXsWLrod>oJ^DVTElY zO3`>L)HR*^HG$co>~Q7%0?KjwEa9XKrs>{ENIE$mrr$M9U)7@9!RrcX^Kq@rfyStZ zel;^S88kP0Cl&)uHZC*_4#I?>TUvqRHz6kQkdwoErg@2LV*mLLy1*V2>6Ut~k5_nz zPy8LZjk^-cT+hM_X>$(nIL?FJLOb7GpFAX@!o&rMMhU4#cP#kVgyZb|9GY6hoaEj4R-FbgY+<>EGn}DxSn>X@iO2+ zL)C~n5<}EI(T!Z_?PPJ!prTqb`=Bb&>_?sY{l^q3!!FrxGh$M2=d8e7%@LQP%0TZ6 z(xsg_iW=FauHR+>C#PQm$kMl$+PVCjuRFgo`KmLrYqCMq7(!d+Ky0Wm%Y@FKY4<`)cU&l)JqW!^H4Yy~+v5JNYV2&tpU@9xKa-8WnLLnhnQVF%QMmk~B9Lk_*~rW_b4k~6cy zcZ*?lY2L-8GWe|V&KsF%k<|R{zr|Gkr#WW7!Fl!UlDde!<2j;YZDO;e(dS%%^J~k8 z@3;+JzsjKpzXHtq+)*wMO!I6opaFa!%5;SK!0#R$?bLW~KG$2cElM%u23^}H=#2A; z@Spede_JOm9sWrL`I5`;oYX$gx%=<(b*#TtcRZ$~G(;E>v^>rIw~I^iYF7teCmf~P z_%`KizCnNV=LIqO0PMvS@1rVvQowgIQhNMVJdU)+xKCqI(}rPMwH`?Z>P;9I^Zci) zFCH6TCmWc4`SL|WN2kz%EychJP;U!J%gikO=5v3;bM&Vr@_c)gEzP8I*x~e-T28Nj zt$C7Q7jZ1G5_nq`C?l<3{1cZ3NfhMl*gVZ*`FK&?^H9gzs_mPC|rF=b#s8wgQaOkPoXZ*6KK)8(6|UZ)w}itS__S` zkVqYBRqehAOIDS2>33zeh0d-wlDryJQJ7Uj2-c@?N2kWu##{Ktqur^P{&W*^R_%Ty zia672#{!c~E1C8QZ{N5W3VDSElz!M(&_8fx2Q*@@Uk}#%YGs8-y5w2bn#Pkf;e@hi}$6)N71TFN}JPTP^R{80eBeI52O2T8VdO>$a4r z4>5=63YgJNzP)(ofVO}T0KQZXWCHSnNX{j-V{8|%m~N3Fn+8x(fC6xbV;;m#uyxS8Goxr5<#nH%R) zs@0b&vn2&~lS*Z=pvbAJWwW`^OWi7mx@xR|UwioJFIV|mc~``T(}f{imwptOw^w7+ z$ayB@t4rMK?iSW{y_1W}9=czlKxKn_1pEU`sNUcxo^3sz!3LfWqOWHIoF zy?T8yxu&>`_D`dG|01v+8QewrJ}V__eR}?mrR9WZ86pH2jTc{qZXkEoZT<^+_J!Ny zKODU;_U0gLGxuS8HQpM({ohsf4T(MwQN~>-xJxIy0&h6V$ggN_yK@7AYTt8_r`=%X z1T+MmTm)f!^~3K~ahA_-J*}#iuiq0((DOm-eVz9@C2#m$XX{jCuJfH(YYRb0nh693 zy99DgKZE(Ty)aJ5o%L=6|JBmbV4=#IfkA}pyc3MvAsJ+O_$k*be|8;nA6+hvP*g_a zT~3Y(Mz?QsU&9}7gl^wGPyH&Z@CRT1qn4C8zsuWLCG$(!=Tl;DW-XFQpNAbWQxg=uwB4 z;(k%f57>g0IPN!j&wsWa8|OuG_f2j-5h-Q3U?VXzt7CL=i>#^{oJZ0d=5K{Ra4n2v zXFnTsPf8CrWK(1v|H1v*5*5^W+Zt-jbwOdjg(k+eII~QPEM73eZVB43oGw`+5leK2 zNH}6Ahb5LEUizX46ozcRq~K24(o#ueW({hnS{(7L42oH6POFA;QkSmHNq^&zO!N*jaiW!@;BN4w?h ze?M=iwCvIrnn&+M%+e_6UvUe1g*JUGbL*~XZ!bsX;V5M{v$IB#4KT3sPacwatn7LB zA1L+h{`-ITT-boDRCJFZvj0G-$Qv9ejt0)9Rw7O{S`rrzkDd`|QgHOnFk92KqE!i0p`S2#Ih&|wT zwA@jV2~ni$JNzEzyZBa_=+%(8{(w=N@8!=ct$JBwkTi<|u7J~=l^>uRJ0Ck}HYk*J zM3UoX1I+tIznUk06f78zayNQP|J=d{Jqq1xaZh+AkJnuG;UKw5|y2yF>^Ttb>4VJgWMQJeil(4)HHm zDaw|xXLgiz6?HuQ%2Z`}2&E~zv6sJ1(F|F9b^9||H|S#~Qm#|~)gDQ@l5fM^m2-aj zFsCQ&8=)$vj(QDkgrY8MwhB;+Ssre zI1VMbtEZ%t7{+QOe=T~}hNI!*`G$#ga#ABBE&ME#J=xltE!Eem34>*HNM{Az<|2tTw+wQ@q&AAx+YpCAh@IFqrjgH)&qO5OvswKJ6Id!QElFcK_z|73G@^V{J}E5$Wn2vKgDd2eAdI zg!^^I*d8yF9NstQD;5TxxE{vGKUU-_9@D2ccu}~GE-Rje8w`+Gea~)*FICY=2s-6) zvkPg9FlH(#h0o`la!kZ#~LW=2>n(geYpp4mz~$0C(k2+vd=Ut66uIn*%*|%_amM-Px0r%IzDw&t zYF-c3c*L2(0O_Hywl_pEe9iutzHXK0t(_A?jLlBUQvc6l+yQo2RGKIuqQ^{}Cs58L z_P$Ya-g_4lt0Laz`~Xj<(96Yh2isui8OT6bdU+VdH-cbn+?&Y$mwqWft}Wp7N}onW zF@3hVbKti^NFV|Eh)eB-dg+wM%Tjp}r!uD$TCOglweKJ?mC@xnER?18oyB&VX7Byj zrMBkv6pFjGvb5z+Q7(d>g*L3UHXSVUSwC4Ka!^=Qf+;#2ucs&%3KU=m^MqIsA$k0P zF`^#1Fbh@9=Y0wa7KSiVg~+Iz6>hn>^w5FC)hLh{hDNvb8f=mNr9gIn*A31$(y9E% z-&z~w6zdn^)Iu3E|2r#hRv>MX%(oaYevO(@4Kd2u3gu+#0@3uwe#dFtJMYM+t$G(1TYHf*!Yb2Y#uiyD<0W|+PC^Mt*terSQ!Uz5o zxt7fu_CHnc)<*eXomwyap^$NPGx&p4)Gmtz$p+C1(KF<7-kzfwT?P3B zW-BixUnEbbIIH0D&&kzIhUkfj31)8i8sBIpG*&d=_9drDdnt&CXy-ISXN&&8?_?#U z+Uh#ZBv505^6AF=+tKWTTfIdK;mO&`OK#qQU|8bXq<{qWUTX7Kv7EdMR~muMKsycayVR~Ks1WpoVZ|IgsX@G^fdsa!*uR(u z0{Wi|S%~eM-=#*r& zH4%~hMV7!(c|GHJw|z&qMWBC!6&pEcbnmC{Y-A-ZbwfH9-4j!@&1VLsCe7$26r9}= zjFRTNp>?{o7b@)fd=L`r;eJ0zTm+Ga%uO@*_?sQ5(&_qXBg!P<(ZK3HQiReC1#j)j9hatkGL0jn;X!?m9ow*pGzS zzI;_~)9QJuiJWiu>w{m8eIMuVu%G;)>@=eJaWOYovaLIgEgmE>3d!4p`}r+v4YJ__ zPO#whsRkk)UzDFyf(b!XLdo7*At6U?k)0*`DwXc8p>43$%mvI&eyLVEBa=R?u6IP) z?o=PGY6n|l8beEjwEfXuOc5sNy6S}e=^prg~!XdoFBOruXLi) zOm!&@x~AqSB{;KAE>C3qf+RhTe&bviAN;{ZGY-T*ZoN-My;$NjjkA;O?c-2CDFsvADMS{q%*6oOb)=2k0bFB=2$8Gf3?FSIV5Kk+ zTqsW`^&hT_Ila*L3kOQ~BsZK+Ch+83)+F$TFV?k~PD%#v#XqIZ3bH%sBEyP`hrn+} z=e*z(?;>6$h=oh*Jy;%g^5n6aWk!wbrFY9aRslCYdXFD4l~1`r!5UTLdF2)ZX*4NIjFaP=?NY+qUNpyL6IT%h_ySE-r78b^SJzZu{ zR9>!KdIwVLL~3yyG0t3ZIoBI$QVo0o81JhT_k~f}mE$q)MkQPgg{|@O+4@tS#aJln z#FrUTsPPMT1fcPWaIgfWJk!GE{}YOQep3M?vK{+ z+6r;|;3)mz2p)0jTKXme9ug0~zhxT`_9XGKpd2Md)){XYQo-IC$Csd4==!sO zb|?}Bfph*jeNgk$(DVdg@C$0FdlNR{r)j`;sU|*`(;tH?kFHf`y$>+A%Z*P?NMf|v zV@F0WBVu%PtnT*NAaUKRc`AdwNX=+kqLvTvCu3ovW&j2=^%1@0G?gt#xU0}nCml8` zvpfQJ3T!{QIz}a2cAE9eBlVkI-w_??H-1B+LA8EJ0Mm?LxeO3M%UOzeH znFpQMb$2noX^P4Ck0Uc;R^;Nu7JTRyk(Y=a`a_F}4`1!6 z)1xW+ek<25_n_)GGYy7Qgu$q&FvljQb?Q^>(!X@hE>SVnlXF+SjQIXtSTz>AqLD^N zt?4HBl1YbVXLqN2ViD(!*VR9AuCy`Le;l55{BsQ$vKgSc_R>B*|B zVJl3d>L_2!#N0g3{Ffq|__TEJfY|V;ukCn)c`r_{K72vtJpjp11-`y&b2N~3&xTWl@UjXAg9tf;KVos+%%pjo;!YBHb$ZTL#l7>eEucPIUm=g zyXt1WfsAN8TX#mpO1y;{sQ=!>DzF(D4RCqi+s`ZH9Oe}ki0}KU5)H%I#6i_nF0E&4coNbG=Sk}C62j~> zs`6U3?c0hEUTSXQ2r|E8!6Fm(DH`U`45pRGZJS5D-NamM6TN2LUUhxCz4c_Pa{47x zYIsGa-BaEZ&A4p3nfG^=s0E{B3n_ACtf_)^fx}|c<3k<_Ogm#B7L&JDC+Bsc_4Sw+ zwQ*spD{IfmW%{4pM4?;(R;K#DjxSZ9g)Rp{NFv)~D4|Pz6u|M>>mg&XghtfY({L8? z0KycGYxM~a$cyhYMA_b$r*m~Ir7f|G%_RdxO&?wPbUrp`DHaNR?IHB1fccyTS+$Or zG~CeBoQM$6j>_!*z$y~MCB^+NxFkK&B>JkTB|f&G|HgV9%){)s5)0-LQ z`xj9YrwcRcRiVBlL$*I=L8}-CzZ_&nek=&-{SIxsC%@0~#9ZGB#4^G)x$*JVx!vA6 z`Y2#5mYqut7H?iN)hBzSX(a#l94)gbFbo>5qLazDV-c7pZ=QJV;X!bX1^w{<#10e?59T>P%H_eoypuKk%P{Ml^nX>e5w z4LdR;X=;w+NP}j3rl5@we(h+xYb!e{MbTW}$L(4bmXSm`eE8aQpYDE3VQifEJ2uB~p8i`%!(eo+7~kl!q*RCx za_$T&2*P@n-2C)PR`O1f4vIpGf=f@bip%l!TQ9j8c?ft z3$17xrjWl!85tRiii*@ncA%~KRuB}rCm1Irmlg%GZu>ngAtC2?zYRhRRciVt-&OnV z9vcQJFHIL!ND7!bp6me+I-G1F!(*t=q-@*!5=jj z0#tSe%c5OnHe+d+d5i7_R!LQnLSksH)@|r+!))}d-LsqptKn2&KZJbhFPOeMZ`R?8 z;Yo(QTsek}_{fWy=&*M7B(sD31GaVSaqNc1K*rzCEs-;4`Z|?mpv+4d&Ipot;EK|Z zP%*&yH_tDm=i~G7mjj+^D}CP4$MiF7GtFUc=$7d27c~;8T}TskJ^awzhds?PA=O{C zyMEx-(qNAERu9t6IPk7+#7|#9z^k&ZN=73v0`(lnJ?XKFTTRg*1g+M09Rs9=@wbS? zj-1Om21aS`R-?~o{07n1d|;?)a}I7}mtS-;Ncs}8XL!oHy^+t*g1xC1KA37y%u@F3 zh3oE(>p5qsZY?ESnp4-j7IjtNCF?&ZM%8(mx%`1xX}nQXoJzg)SI(}f_K+BvuQF9GWp2wlYy=cmDPI{IVMXzFrS*B_fYM0^&M z^WMIcD8}Y_i!E!y%ULJxghWY4sK;00r|Y@w8!u6sY=VE+NEybl6k;HY8T{LzUwVtb z;62)H?z@(y6R$c2YC-1O%d38OBV#%0Wn-B0jofqcto~Dk`#|F}FiUe(?dLDA${WK= zMND;j%t6#2DTdFjJX~xemjVOEMmB{T7d%6nJZ-=~9r_Z_sAsi&F*`yQ+Jh4g)J zMJMztnYXF%{@fxuKHQuh|E8vCHCo-@ihcG(;Bvhe8q&=~fBmwu;{wHte5wCvZAkeM zI_2%6o9xKj_J+xS6Sbm7GldjAOzNB*G(b~ zkKKvN&SDz{SbjOv-?wWdpTnU|+-z@`&X|dMoWgy_miiIp%!4ewFuxFA)@fFcy1Rqr2s9^EZbs;@Qa3LGlu9jsp(9v2Px?kv_S~6 zc^P-(=u97Y%TGP^nxjZUt3>zkdm+EYOvTSemm`9auM%)J4x0qn2_0&t;i{80nmvu; zETu^I^Z>vb(;R%kfwb_WsF2WGxc~1$mim7dGTd`e0nT|cVZiCH+}jYY%MGZ>@9$Js z9-=IO6KuWb!3@a^AO=$?I>U|`C>sDnvK!E{BWx#@0*$)%d~EM;Am%RG5TafiR3-#N zYA-iJ;ucV3o5D0Y3myI}?7o%s#ThVfTcu-YSgN~s>U@3l2L}c{K$>G~$MQFgRAO$J zip#YpT4kr$ETm0Ds$`_(H ztG-lP_qvtpSEKKnH<)gQlId1i3RwTT$E#=~4V&?m%XMx*o~{{p@IU>li*d4J2kJ%) z5IDsj**+Qip?e%*FMG8XG^5S?G|1jyLCgkM2v6twk4>#@L0%3IfQ}=jJ~$Sy#iuJA+W{(0F;{NuF0I?1lg0VbOaB^6wyjZ<5Iqa)^&ur(Zk}6}u!x}e zDn4!V$z#16`do5RzEN|XN1uCR7=T#~<)bHI6;~bLJndNKx*To1uZr4VtT$$D7tNV# zy#9(S+UrX8)y0g^=lS44Yr1{nO0H|Mw`>*pt5hz}?-&qFr6E;jib7vJg4?vI8>uil z<+||&tdVDZuLT62vfynPX$f8^Lb^c|k@8EmeRr=MVPP~MUvqm0Q5FCSE zI~>n7BD_Jr=*5!GHZz%)zyIVz)1n-F{EkWv!ntDl7yn?uwr{*xR7lqizn}GZ1vX{$ zTzj$qXSK>;hA%U#GsEBC7?#@4+M46#c2?4O0%2USpbMON&m&CHiV+vPNiu??K$jC+ zG(NR;9alXxtYX)x%$=yQU~Mf_|HuyuXo# z>WK1mdm7L_Wmg}9_zgk4i`%#N6&!|!G^FX<4p#Vt8t{g+8?%$+9ET4_m;NRfhtR-p ze%I1Zf#N5(_5n{fkVN?Dcw{b!#{-N|d?OzViaAN_CISk9HKd`v?m2nm9*S{t9xK># za8TqpJrYzCrqs|t9;07)U1TQ$&kkhkZ0GO6rBIfZj(|!`ttgl08o&89u~YFCbT}+!aO(({TU2UHD@m3hlzF zO#nk!mL zsC-E2#1p8GH$8O}IY>SkE;wM()34G^RvAk0;fGK&mR+PrIDR^`qShlgA5S?4Of4LLELz`o*U@d^b=XjhDN11Cao!Qd24i$Nc->$1uG2#9KLE- zQ$_GJ`y)yT`F+^skeB&o^`Y)h14oM>M03i16{}Z@TlZmgcuA#suc80x6#IoABZ$j` zG6MJk!Q*_zE|sR zY0|e_Gcz{pPeSJDkNN4G(?WfAhTDA~ARZY%)?kmzQQ|emeHj^HWzgv1gU{B!@S!x% zIqBh|st-@Ju(1U-u~=2bLg3`kiYt*~ zYNwo{Gjd*BPKJ^bVq`$dZ2701Klm@1!#rWI*%ykj(<20=ooaWJCqs{_4v#NTs`jrehHa?1-6q^(Ki5;OTL-~^o(J~D&KiNv zFRz7?{gi|ixtg|6h*^*5ew?AaNi~vEz6{7LYL5SgTvimJ`g#H6#&Xhtd_@q6z-_G? zbdTV;FObYO)E?X|4r3-rdU{KjZa-#(zQEX2E%E*k>SwBgv1x(uj3$1tVUNnr5x~Zq za8^X5bEN6Azk6x$O;gph@(|csgsD=XHY~qRe38azb&byWt$`@Uo)7Yh)c6Fr{3`y$ z1v7S1*^Q(Q1r%5f|Iix$&6^4SJG+g{Wos2z9xVS?CKAc`lbRX#69i?3 zAmc~tkrL;FgaLg&34;Pp*dTxNIOn|dS%I&Llp~bVq~HmWClRS8VcxA_q0iW$P_*U1 zyE4=+Y=`s+B1HsiQ=6t%Ec1m$CKBiB6(fD%ja832w48H*$0q#+B!S)(Asy9H^0SID z;-LyM;`)cDh}fwT9X9TmX%BQ4q&Z?5>1JgfsU$-)*FZQFo9@~&?7!$U78h~dY{{))3+ z5`0`Cv=6HN7h$0nlg;YJ!_qp@>c{VaTY3h1Vo>g5!XYsZ4*VUQ23|?z_D77bLO_(d z&Y#>Vz>8Dg4cCQ9k{aI!-A8d;-HWtNSgB}KMK(aXeBfQwUZ%OGRZ0$P10MfhvVqZ$ zveIuD2p*duY+Fv9pM(vn-cMENcI?@($Nh=gJP+*J`%YcuHcpl6sM~JIp4ek!a+NAzv7LKNtxD-%u{LWk(jOQ8WslN90qiPOg#()gEFr zWO1#uLofOpFUOl>IFqAj0s1N9wZ6l;O z7F^wWBJdXp2wPsWOVIZ>Xi|rM-w=3fPYZ22@+r08NLLW08ad_42viDW$<-%^_M|Z!0P61 ziIljG;OA@K|Hsx@g+s}E)x>I^UN;;%VT4|7O5J5p0Kw@Zc=oT12y1TojQ&Q<3 znjwa6_WS+U+H0?a{T|IVb24)<&-KK8|L*RtDZ&O(LGT-JaCrbJLKV6?jG2MAf!^DN z77c{}n|&we;E1S13>TuaUv!afw(x0E8qs!o-=^Dao2w+``F5aT1siqX;AZyhveeraQUU6>3`sCIH=%7<}Kb9^QQd7gXwFpi6IHC3Lr$5`Izt4Dyd&K|?r7L)h z)N3mSP-`VFdA9Z!HhT zDra0UL`6%=V_6(#BHWnNEPJ)^P2#Sx435*!IncyfeaIMUWA&B`w5d8y! zv9jsacNO|8>Z_H6H~01E`M;}vi4hCozT1yLMikEHp@GLLZsS^&9-akL95Ho&BpXWE`2bLENC+pu>O>l(zrmh zzt!l_UY>tpV%ng=yno8CF@E43;i9Qy7}_$$_lGg*+-JZQ}W!0>)t&lsGbD`G~OgIM~Ye z$X_Jj$n1RS(s50xOwK8{wkAEdEA~sK2TSm$;O?ISa#42#w1GynXYq=Ox2lrfyVqQW z0txzrgWWY+gq&-+RJ6Z6V)YgI5Sg>!RV0C(fW0+|Re3|`OnC$ds#FI<0<6?;-UIq`X^<{+_tuuSzR**=*KXP@&C zei0NktLbsc^?pCgxGZkP15d<;4(`EQ1#y2NF52;Ye2ivoAC9kwFID~PVI97V8$D*? z#8XYFh|RTbJFohR+;|{6@*irp&%KT!iNeNHfgQ&oS*oqHU`IHvq9b`+CHq2C8-~=X z5YJk!67^82?${$c*~2^5cIf85n6RcB`5iyE)m^r8+>UjVm#d;tr-SXHK?0*O{!`LK z!=2aMr59z*z5`?XEhw5)vX?NUP|xk9;z)o;@ZWUBFOybnb8JM6W)RYz)!nG8RbQH~ zD55=6^8nw=XwIOuYw8agbFjn2WP{FHIuKkvnw4*X?W3xvpW@lm_crgs`MV3188UZ@ zaHYah{P1Djb`OOL+XcC?*EQKo$^|Lq8&y1f@@Dh$~#!ZIgHmo?cvxM zDWV-A2g05vfW&2NpVr35vpAvtU1}Z=fw98L=o4FX$}>r8p{_QGxNbt$;4aVqn?QKfNqEmOI(vukt?7 zOVr{S>_rKCRuSF#vCF@=q&ZbCi8W0KT-s2ctK}wU8|o|Kk_ehY@Cm>KEOrliEOIO` z#c;LfSoyx!!$`}%*;`atzrZ#@%3AHBXj`F!#BA+e-Xkl%yxwRn&CM-5rF|OjmD0iZ ze^85y@dTg{UU0k*6xDeref58Vi2#@XokNLb%53vA9UYQJtg%2R0HQ9r|5T*jkVNo( z{2NmhBRC6iMRyUM5xyprBWM7#vjf1Lb_`^NadVEnCeyRU4xd((30n}$$d6x8*LNNR zHS^2{F(nlJ;v`)J>(S6al6Cw{%pi(!K_ZoRgjodJ@7N_|L>)x(6RANffoRwyrQ(Kr zg!)Kh@j#)#p`|6`zKv)y4{|PJ4LSOOvkMOe+Q#M6rS_&KVWvnQvj+PV%dP>BjM_%W zRmm+CiIoH+9i1RC_aj!|Xi1cZmbK(N%xi5nXX=YylZom>ZS}Whq8Cnb8T zI>vdC^B~s9@N>Q5N&jt=D(psI5=bN|h}ZRj0$n6dVdfqN+UN8Er;oy2)SM`ocdydm zb3~|sbb>+uV>1GOC;V5;;ST@exZnuHiY9W$cxoZ)>y{@|vLysn`+S-qT3XG)C_j@Y zvMP#4rCYS0HZTgHV+cI0wzok6LVPD1U(8jSc`Ig^DGtJYfGVbUuBigTNPiF%A z-BuP4Si6$Gnv2hhkC=;gxFG08Y#^gOZKJuKx)~*p`zVoqYl23ceN!RixVxBdUMvWK9H9U$RyoOPC{4f2q=po`!yrulEQ!Hwl5h0x z3!9`Tzg)GsVTZ>{Sl?LJRQ{^@@b%D%`yqx4u9v=@X!l}q>$N7SR25M1W-IYqzU_YB z&2s0p{!^OFyJ<2S8QneOx>yCddwcIJjF0wa762+fA0Crbczl_)-_4jHuqx~OVDeFK z`R&^WtB<zG4%eoQ0%e?8Qb3^u)r1Bj9=1=;|8Dg#WD1XBbq*$ z-S5vjSHSLjDD0^X!pZv42_<%ODZ1Z%J{OX(x90ULD+#+|BDZ!sZJ<})i>iHC?RgA5n2TEqyy)EiRs9?L#O_Yq zd$BGgH-g1jLbR(=*6-RCf(>NV4#X`fP;)m2&`JDQ z($hV>`(*YX^UYMBldjYkYkRANWNItw<{8b^#5fme+2x7%pyuTYkoO3ObLfCqcf09Lk#WEIBVAP_o_N>m{yx1C>Se2aud)9cIus_(1hquND z<;>${C={}=(DHO)@<{iuKkC1{o(J=>|EYc9bVusS|LYEleb(~rv1g;gMUTnE3)J1l zLU$fX>^jsyg!fLFp#`c)1Ow(T{}_LN`cR%=^I%|jwMW}%O@-NuJ4PF6e9rFYEC6`W z??%}Vv~Q<6+O@cQfG(v@J2BEm48s@0OTRJ!0RG6?C!u<1LAC2h81)(aEsbn-6qLnR zgvDI__AeoQ&)N&W8JVE{pv8RwsDyMuv!s!gJpxU1jq|-v>`?YK$2S z{u`BFipr9JJqV}$T|6_}dUbX6@QhwxEc{}YR71g|56P@#hdbn%W|sv+j{ym|%y%sZ(AhWmJec)N(LDo2$8XWRAu3+WSibCv+w zY-$Ty&dt0asvZi(wSFEHz7`xCNyC;&YXgoXX;l=S;CH_i^bF4lm#W1pOgh}BP-2~+ zE;#XDtth&vr@`sd)}{qkRGa)~%1tbwTqwk^^KsR&v>zHBHrjovyVw^*);(r+_=3F9ygm&YcvT2HeMrF?_NeU6Bj z3t9!tpOw`fLrH*Bl=imsnoH#kjYY*Cj#$Ly$rfeqjzqZbvepk2**OGmPO?)PW)#HuRR^xq}JYeT-SY1 zNoS!pzBjkpLm__QwfkjWR=G#5jFTATK>RlVRsh1eP_b~dVKn`uSaE z%H^@t7goSR!;evz3!TKEp$#IC1WFtO2c;~!kH0ihmPVWb)yk^C@*P5#1ZL9PVU<63 z((^7a?-PihAGjtp@8t_anoz@#Z#IG)6imn1@@z8uuB50H8}!Bcf-Z{KM3`1m$=VhU zRhv?-yR~|>s`=_C>H_ld#$6L?Ftp+iCL{2cRifL+RZqq(BE+-+5eMW&tbrIU@68l$S9qi$(22n*(KgG zs?6HcrlNe(TYKtZO3m5Tv@FQaPpk~%(0oS5ZJd=z8bB~o__1@>=7vL^bV;-1g8%U| zA=bNCML=YhhjotOpNElWdm}F`HzLpwMt}IPwSeOsgBHR?+cn3HHQFu4W=1!4W#NZcK25 zOgV_QsPRL!LtsBA>1pauj<);mRF>oq=x-;K4R;9t5QY=RY7(6imQ1R%ixk9J`WD#C zlawFovw$c9sMjg`YCbkY0dJNdKYkD98pQw**GtWlwnaQQ=q8H~geR<@w324g+!jRj8%ve(n3YWrsXmVA8J! zOU`hbh2&SWS2^EcaU=`TMeK0(L}Hrdy3fw?UL6GKSAp@ixqp6_k4OSBd}N5Mr!g0WjptM*_6$M;>o3p$AxR#nM;vnEVcS-EKlJZc(@}pmIu)I0s&u}WMeK5EZRDSzfOW7f7_gpr?#3OR4;EvVddCMhs zklx*+?Q{pe_~N&~RGViD*WvE~?rFx+IAePWUQkj6=%8DNBon>HL)l@3CQolw8UUDj zOFSv|F^vE2)2SA&<#F|I1#AO-$4tVlo&MK}g6RNr=`F7bm(Y`G)9Ea)QXm=aYfRg}XDew$-M+B<+P7NHRbBB|-I7$(!sy-B70OKOX{dyr z!g2j<{y z-5#sd%UX|-eF-8MR1Cg|RocK9DV(0z7#RX#0gPJ8%?IF8mdRV;gd5ziCORJ>8_k8iZ|^Rux=U^LRL z#yHrFe|HXmZe)FH;FRt`M|tw;_zK|K;%ehkC4XM%mKgx_Yg{~kouC;QvpW76oaf&- zEV69a`s0kg)Mu5KKcH?qdEGx9_&hp>`;`!={l9iDlMRrD92g|LE{oq7_sMB0!`#I9n;iTrlw6F!-pPxt zacK%AYQ{#~Ci*0DEvzcUUlG>B$5dq{Q9^M1*+Y@Hl4Rru8RQ9Xn-GJLmQe7WlMxT+ zAKP+;ScM{mWJUJ&A4JICCLf>$1z)~KWu2DN%9kCkL8IG z+NAy0imD4-a10F%V>2@=rKMns^n;u&OWPy7mY(4@`@E65QFXEKEe2FeR2zG#fw+f6 zpY0|vhpouK4Lo`98?{w5(@rWl3Ie#<#|5bAqKO-4hq1XS6zoL9v!XR(V`Jb7v5NG= zEv$ymh;E%C4bXd%W4^An&?{NeQH(inr4j2-anF+7b+uq3K6=edHY7b*i5A#2qkcej zMKvqo0q|w?Q9oc1AX2m-|CL<)F_lFcs-t(|hsN>u>=MD+Dm`^7Jzz}uoI?0#eJQvw z9Y^Ld*GSwm4H)M`q?O;?SmE21r=v zB2G>P)pvxH?57hNuBf?)a!fCx zTG&lwd(0$|+lDhZJ&`5y8;AMFT?~9~J){-ldqalA#Bw7(b9kTR1H3Ew(T%kuO_)Z^ zPc&2_1e-9)mvT!rMq~MufGG-J^Odhz$w9ym$}FWO1D%+-56d`YWu2-#A>vDv`pX#7A+8%H{ zdZ1KEbfJTSj#UY&CluBK6MMyTD$j9&5qOW*prduz3)@0!1ft#huM-jz$ zDGr+Hr`k2Pszv%x!)`D+?zK^MQP@6r|3GX1w8zu2>PtZ-_!#_#!~JkP^rZwbAz?g; za$6Q5BcZr6YWMeU0!osotY4ED_-X!5ar``|J(Hn0X#so0NnuG1FPqV3W6eC#nJyY* zwI>5NelmX$%8-XF8zjuU$t`OpwB}4KDsGFKE~LvTzG413Zc6;bY9gHm=?1r3m51b0`_)^NC>d1X&b&*ed>>VIsCOj zTs9hJo1dRQJnvHXxFM)6Llv$8NcAC@j=M=!8YmJvp^Chb7n6a??*TcjI2&d&Mlwc} zt)@b<+<~+Vn*$myHn#RN#>TnRC2`Zhx1kM?vrqSzi;lzjWcQ3|A0Ar$o;o&&CXg{2 z(PW;eF85Y#sQ&lyi_Q?je*yql-9F)UVp0;jtCL;DYl_WguewcTWo2!8I?e}xT|`t< z-ewO4jGt#@hBCq^f`P9t<4>Zh;^95j+4XdpB3wi(PD{d#)an4nKSo7eYMP&J#4-iy zQ`hmT&B_!eOaES3BAS1in0EM9AAKN|i}L}4C?(_|)YX}@%D&%4!Ub%w^id^qudtjwdt?z^oAXi^%!uU6~P8tFb{w)a#vPfPC7X**w}CfjHH03 zt-R6l%jYjy6*V}8CGRIbXa;^-Z%9aFOR@w zVhdSLiX+>cX~;&6iuAXCr`A))2kKh%Y%J>w*pTW14V{P?clVV1!DQ}P1kV)j_lyq4 zG-K*@__RU*MB?7GHyPB!V?6;Ly*3x$_Ti(t^HuL!kFOU_@xn|j4A}1v8OCi0ijuat zd9kS@F0J_@)(D^acWYpCDL#YS@8=vwt#qZnl41E$y%vu!pX631yfZ--_{d+( z_geBe503|mB;LzF_h7vKwYAA>9x#?91rn`e)g;(eYSY4O1A-9s#WHf=vGQB^eDB>v zdEmz(bAIiJ+!mYei+M-k*(pHeV@eC{c#!ICeM`*a)&=a=(}QTj{t72+MLEW7uNUTF z-Dh~=rA8-M3~ywvPs2HzJlq3X^^BSzuF!IAMPaY@P&WywU;Dr;%i4-}$N%%hYr!D< z6GE+&_(BOQ%;I48V!?Ll4M5PvY zqV|g3*%rAd zuZwI^(G{$Ay|O8Y1<fs5o9yDDa%lUsWJ0WWUi{kG;g8-JAQu-Dx`jtAJ!b z_gcqBGK#&ZY~!W$`3EPcxmqX^cR4HD8q3R_`?~QMRcKZaEZ`DQp22utcW9n<@XYFk zVlt&jkM#II3qQ9f{x$$!gmTZ+^8ZndH2$}0WKBiqJ}c?h|L8`ZP`4#!qsaBorLT5c z9zKid^x;1hNS8LB|0 zZhRnz^X%21>|_{Hi)g!8rp=EfCHRnD`iFFkc_^6!$zpE=Ra1HbS2zrX_DW$i(SP&9nc_IzAV{6NIbAipT+>^N=+0w8JUcA_mj0QmPOwb z*o?2&B|H%Y9%al=2dnHA4Rr$v-BoZ>PIkq4_E1RlmBUfSCMT~fMv-Z z2gb*d&GVOew>~k8m7GJ?u8qMv1l8n#N81Xe2AhrOIzi(`&=l~clUPcPX7XK znwKENczo`<`KOV-`J6;+c#N@io9mKEFv}-1d!ic8zaf$Cez6me*v`zBs`c$E-!rw9 zN_eBJj?zeHWQ}%Xtd=*aLE;~IYWB9!=2h!o6=wrHZb$#9`q(8m*MARAK^Hg_>*{uV z*6&kGbEmx@Ydiss?EWWhv{b>_mtRX>1YKKg-Q)3P?@ng_N*y!xNauGGHclDUxkPUo zDVEH>m}2=k_YIDg8@!$qUvB!ECv1xQ1v{`iG9Wr23gs-%IwLqZF}4}VKCeH|&Xw=v z#HkmbREzApb40iJ=<$kyMYSiPa(jJRo}Jfah;r1larpG?oKOM3P zK2*__HXhmkbr-AtvRJ8Kv&X_=d?i8Vc#r3jR6Y=yf=xgyLbDzKCs2(Ff7=@hhT>s% zH%$QX!4%O>Ai_{gtp4j{rCzxZM&XaBfifW$y@Op8Z#W3v$};e7^kAUk;=cvY-BAE~ zRbv{_?xj&&x3P@fiCT1&i~}4hBQJ`BWI!@av0$hR+>3()Iw;6ri0$qh%4knhh>CvV z;cd`0^UwZojO~{P&i_V25#Z53xZD|xR9w1e%;nOKh1-uZ3?9%_(*l^-|q==@G43|a6gI}2_R_!!;AeLXo zNJtG>J*gvwYXIW^B{Sn0ShVH`QEW=G|BKF}{!@r@_1C{-_69YCRODp?3-j#Nh*DSm z)4!j3#~$%&3o3ur^ifsWN?NRl_Kp#L-u^vMQz_NgvQ=9JUJ>9(yTje~tEbjh91o}t z{%+eTq@qgG*V~-y;_vafMJl97(}!2^8ZsJsi&45gPR?!dny9AKsiq3E4_8mq&=0Tg zf?Q+D8(TgK*qgY&G$^b9nKVfO*0(X`dmgDPBGLMTpb8Vu@Sy{YNxOV#c7aAs4 z7>O6|8Y^JjzTdO4nlAq|7mhLB{gF?|?8I*5s{EDj9E(bG^Cx@RM>TlmF&`nnJ2 z(EHsEH9xph4fUxCn`%TuPpO1;!DNcgYH;w8E61|t^A}f*>l?G=4o6?j4>!@g#_>)( zk6iU{+JkouQk^)Sh&F0}f(1&+6wkg8CM`p)M3TU)XE>JyGa$)IwAOekC;A60H>S)1 z$04AQdAyKfX;|CY^rjYGh+OHAB{=;;7wNU5gX2@)>3o?9i)K=>O)s=5)=#SM79WcX zLMf`NkA$vLF#qGWJ6TRHBa1>PAW97)W~O((O`^ElB2r23B+KNU_ZO*~Fm5F)Z8+-s zd5mufkB+}~Qy29Wj*ZI1%U_>u61ex}AZ=Br9$2wraavR2!$YX|c1W;P+38XHt~8TN zA+B*-eWk)P-Kl$F$8MH~Fu;>?h+cMciOw-!N9v+iF<_&dv_3NTH~Hq`y-I4`GkA}U zh4G*OAb6uB?DPEW& zd5rGq)roeHcZqHQN0ML3qOXBakIs4)G#Dp|CvFde9&+H|=GNfMO#d{84;fnpz#u&C zN5*~c<6>iMFi&Oh4F5PqzfyrWO>I$wY2MlPUG%*_*eUe4Ds1x|;+= zcGBollB}H$!L%aoX;y)PW2EK(V0JZi0LcRf80W8=;%zo3xyzT56%5-a$33^)bh>#Z zfn1Vh)Gy!W)h@#bVq9w^WrQG)v=$j<@q6>1fIFz@_SV8D5svr=%a?q(58jT}i^&=A zKEBVq*ET!b$eVdF{^OWb`-{4N^=v_ZuH%I}xM^ANX%)Kztb~29pDd2Kv-XFl znwksm((d}H8c)frysd7GUCJePn7way?(K@D+#-Yb`P60-oJ(3hz&u&r+llzrMep|z zp$%+Z4EH2bFZ(1+eYgHVU9mn^5+MQAErJtE8Z#r{VW|XKpRzu2R))b3d>av9p zFc=|=Z(ozp<<{?7kUtnQtO}Eln62fpd&8b*S5phCc1AkSl#NW&gKYG2)6#b$#69u}VH8~3V#5u|&|;K=9$a-(H6 zxvNe4+VHp@W9)NZY3zNkIOcnzs3vtozVG-D`KARQl+D%)9k2`wW#Zrqm@9gf6G$9} zqnuyW78l>xu{k=>IRU<^{IhZs4ZrHly1krD>$u|<_K+Vw^-T3Vkqp3=X%OI-SA)v-GIh(Shi1Ojx~-4mVoW_B=BRcl4H<3_50& zyy6Vnp>wK3Vh)UXE51JfOr6FmO1qy_^w&@{{GUzOz{BOddMPOHfwavBY+E8hi zlf;FTq_p3hOYE}PRkhCno}lC6 z$PCTheA8F*Qb7lhknr2e8jptQMNcQxYE2 z&h2wkc%4XU3vq4w|5&J`CiK^_W<=0(P5tkw(P;Dnarou(9CTjwKxdYf1XZNl9a*|4u;1;$FNwkz^5;r zKFexnfN$$%iu=y3`~tJ!Z;6=>S(YE#a_5>Q9A`hV#qQ{CHfSxExkwQ^q4~nh`yc&i zK^6#%&y1UqGKH^IZ)kG0;vi-*GxTTZ6j6^uP#$5t&m(kOxP zRfhB+b@f-pK_-wI!cxPSrGosf@8VKPn(%?CH-P|>gLerfVqj2_+X-ua>|OF@00mtW zYPu(Jn?0uT5KCFML!jx`ghZ-o?7hjt>h=*Xav#zq0@X2uc|Yn>Hzxgc9;|q1*+v5yVjQG%V;jLR(uR#|BjQsQQ2VCvqngqIOUZ$-j*AKm z!V;4R&dEt@*?9d0tF(wqxW76Ot0YEO%Rob6vLp8cN$7n)t`=6~HuQdm({#MV+GuEOS!V2(^P@F4v)z_6 zj8nh&cFDdbsZHK@#_J=uk=#H6UXz&Z3HYnLe@r5Q9raN8n^DT?^i^du2W)11tMOnC zwZF?7=RuC2+pf^Ar0!k-VIlamet7sDcR{UYkG;#4zT1~cejA8(x}nt-X$=qVy`DYk zz;lp%|9d*)15^VfW4$8_}SLxz=JM;E~YZta^4 z9wXryFzC#Xn3&CVa6&GJQH!mljeev}TmA7@SgT+5eLuXlfxUVb<(Zn|Jpb~Ec`vB&727=s2W zSYbxQQ+}n^Tt9q_A1!UUd^5o1qq?`nUEKCq{_Xgft@9E$U#}xaPE^faZ!lT@yGZuUJVlM)mnAL$wUqb<6RO+R%XuYTMwgxBD~{(&7I&hU?ziUoiV!ZaR*REgiF6`@ zv+(M87QB1e^YVwFf71-|`ey&+YI6Mu!L0b}w)uAWRBcdIh#Yk4o!@}?-Wh>qwnqaI zZry+%ExZD_5cya00+m~SFvxJ)f0s5aRaQRrbpyG3-c=&xK&wgYL+0h;?4iJu?0se; zBn(q^2<4|uEh#1sB4_MT(f7;MpHY^ofBaI z6T`OLrw_d6x=I3|87M~0h-5X%4%TNzh7<%LL}o7RK)xBJ+JPLhVeAx5;D!P+N8RuY z&?lEs$B^W0(_KEWY@VtW*TVRMcxn}|=Fw6Kf&vRMg<3$z`-g zJ6VWaL+M)m?Md(LVW;l(8 zf999!*E(b0+$;_*R;8rrj0}z$cKtxZo{vrHSttuCGrXywUKjG)_7 zDPmGJ_FqM|W5=dK65eaca7>ox9Q`q&u zYyZf%2kEt{>2qPHLbzN#XGl!@$~EUiU#2@q#ZL8O@}DfL1#Lqw0~q82-#2UhGP9`p z;>{a(sd%)-VydTL*;0?dK>Q>UI7I`Ae4h6nQ#grpfiU zb#scG#Nksn=C@arQnodO9TA&X8d5wq{!YfF+8tr zc-7m}mFllcd2fWacC-spL^g{S=U>f!%UIGQO)1R!&vQcZUriaRv@#;_sB^*5ta17t zAL*yC9d;o&wHlC9*4r?23fcI1J@+J@pqs!lRz0h?G{Ut7jU`rYjjd(uO$Dk~F$=*? zsEhndOA}+ePE!Q2HC75U1F{!v1e!vXxx^S^VYr0a634l^8Q73JyQSDDF10p~67Pf_ zK0h!%rT-KO35JR zbJ6ANGKz8u(k^{AOv0LPdkL)W_`^kBI4-v^jW0GjEQ`M6h3dW9BOvrf0ci#;k!Hrl z8swy7WLrB5$pm7CF?~#pHJAB>X~2S-MBv~S$I_c(vKi)c>C&r3A3blK!CDCXpaHq& z4O*F>^L?42;lw-P9oC%+)Z~GqT#vmCMU_RZyULcGtcnOb-%+4HZO~uX`uQ-A$Waw< zv~A6i3cY-Nn=fp(qTuMZS>#YKU)~HpTtmHfXhB)WzxZd#Ka)AA>K$Uy3*- z6%K(+dD6_Rg1Ttp#QLc`)aSwa({Im!b4?ct0duSux2op)w;E&|ki_y-SgoWN;epkMAHPtl)=WUBPPJm{a1ANtEq(Ltcx~X` zskjX$5-1;!uI2Kr@!a}eM9<+NECRn1#(0M4v3K;ldEqX3rw2@$=kL_yT~)^fX|nS=OkT0hI`#L1=?*V2QY0ZRB_n`az! zV|!NLs)d;Pr}PKgS8vy=p~3HP`Ne|=G4@6}T@{B9DyG0^?9r=_0mO}d+1oQo!07jZ z%pQ045f{BsP|Idd+E(M$Iw9|=#$wejm?6)M?>3faY~=>}^I+;tqi@dst(mYJ93QAy z^HEaO=CiKe-P0da$X}AhaBArvcv$8v5K>MzzuSH{JB(6^R1T+<%13BTyCM6=MLZw1 zqfM_>woh)d4`6f<^yG@UNlgU;`~%`x?9%;p|3 zn{w5_&uYz<-%f1&=>IT*@Mr^i(Z|3l2qStKO|Zo}g>_3e||@WCTw*z9OfA#lIoCcnl+z><;B^U}uNn z^8*G>6PhKk`-#k9MbEe@WBJ|s(Pm6(ysoDo!v=B|R3AR7t?{470}FWRK}P5o+t|ys z`&jyL=_>a7iQvhG$b6~A({zPp%rSmKS5gnB%dX|}*l#VO=J2$aYXzaKiGSBX@C^mD z1!X1H>f%BoLY)z_0-b8cjL~6s(7Y;}c+wtw`5Eni!Po3R=rAUkU!_ZEjYpdxFng=F zLwy)f)RjPDGU1{51feoZ^Nd%$Ek0@zcN&XM@P1yGZ530m!}?C^>U!+gcQGc$^M1Vz z1bV-7FQ5s;GRi;_s@o+UXyRw4-BUIGJgKJtB@iJg>!dPa{Of_A@962W@J6E7<&7Vi z*SGBJ>dyG>6z{%z%O~KnYK>%>0g@OZIuqG46klzzzJC2}`nklGzSB3sNDrju1IO#Chi&hdyk0YjSHUPIkzf)nbck+BBQJzmqc~m<@e!^ z-bnUPn@p0UB0HSqY7J^4+gZ3Pusz68#ZF23BN#xXN0qugV#j>u>(yhQ&O}WEb|rP$ z76CUDWDv{urLl8wS?XZA2K51gTlhB!Ca!f*8i&;DbnT($g)e~m)~VwX=fe6gHT&!Q zqBS0`tD{dl9VYfm9VvYx>;|WgmMixUrK6b=-}mDCc`eSB6fTbyJIAKTWlGMi31>5# z;l2aI?x#a0O$KVvYKI%&8IENRPQ6+HadfK3!Q?n^=?qg=S~OsHHt6_-1)M=%-jH8hlz4YRHqT&sP41^EKE0TVzaL6lW+NZx{|;vKssXznRs< z%p1;M;`pR;Q=ZAzd_x?25mf27%E-_ z_G5uo?j3o%`-N#YYvUix9$+r+k4ioB5|3Nbgv~_fq>(Z#5TjDn#vYpTTX$h!-84 z<$fx`CPf=Kiw}Fb`HHnK_LZM3tSDe2-{XjP;zTa23&tU-5N?jmi^hf;kG|)yPsi5p z#?)qxg@+%f{t5rW4cuqamEF0VFD_jjmVLV0Tg{vvYR)Cqm-0JKiChzRfN0L0Uysh0 z2rgLPN`?;;VnOE@jPq`;&WYuq!5$>$$0<@O7~A@V-GE)F#(vLm#ZM?=wf!3JtgwCL z-0AF9Kflk0Qb7z|f7(0ZWFaTX>8Wjg$hk^EbSg7V>S$ece6qMR5r44Sb{}CpgwuzJ zTa7r3UtuU`>}FP_qXN%U+~hw0D>}7F-ox0Gm&@g^zDbklB^Q@3L0;^8CJ>K}gAEpw zX_9r;D?QL@8g#vv5!x?cXP8mH9uFtvaIRiA_BbGDWxTW(kLfhKJL0 ziK;xx-gW(sa6XMV&>Mr#55Ht#DSY|?duniqzP@UyJ$H}&<=df8{#Kx(qJnROT1cp| z(*%CR^&l}(!ZwsHJlpX^2O7RSIk{e~sAd@>9zfjnN+1s0+S=MS^MyOv1`CT-s!0|v zo#oQ|w9GsEqaUc%)d}Y&KlnL)J-hnI-70dqL%uUV(wJm1@Ti8Et0Wx%+va_DwsaA+;)R{#sOI}E*>8zDWO=rBVNhq`LQ9%ys!VdHjEvmGn<`pUfzh%KR2N58_$ znqJSdmU?emulAowj4PRqjY5)=lIjmCkL-w@#`}ADnxBq~gl98hck>6JM2uY-fOd$uFVj z4r{L7O2}?zvzE^b&9VK7xprrK*XQ(Ae?eiK;5YggcjsA(cX;2Fl(J2X`Ih0g zypXvMx}1i}D>=BE91Fn2C$@EX-)FGNZ8p(6d^I#~pyGRk3XxJRSHFBCP=ptF3 z#^E6f&357;qRQI1sAhzSS-l=%?ieqI?=(9-5Iaa*2ie8=uJ;#8Io+MnH9u^ke_mBL z_Bti6kh~EZTe=ClWnVoB{`RDn9x_$ADBZ%`P-rwj`+pdFtFX4ar(O7IX^~<@S}c^J z0g8JdxVsj2cMBG@#ogUqik0GC+@ZKbk>DEKcmB_ockhGu`o49za`?;4npGD}1pVTu;>t1~7 zdukKbLbs~rvKgTc*1XeZ|1N;vD`tzkGq2(tkAB>H80O`-Bed}W7dIq#TB=i*g16u* zf`)-snI4Eiz>PPQ#YW5jjFa-|iLaHuO2zXWkND(KZY+t6$MaD%xsslo&XuPt&rZ24 z5QI&coAk*K1<%}st$O!p=WKQWU*Ah?2FT z!IC)qI}EWMwBm``0ek}XuYQe2M14#Kr$uMQ@6EJR>OEW)E&tBD{KOk9iU8 z1Yt60o48}=E~B;id$!^1b}BGhwTeP@U2BIxfex$P#quNzKVA8oZQz4rBS1c2jyQVC z`L)jJ1$?BM#in15M%r~qj-)5>azl=YJF?6qgw<gmVAXTY>p4zx{Rv>d^#8A+bVVr-CoUlcP=!fOsYsN=D=QDR-&8SFCIdVOJ=ng zbmlZZUxyv`b?ls;c8X*^a9El8b?huN-ux%>$=~1DL!*EDVms-AAEw8l#GBv;{-cSj zx{Eh%8}n@f*N55a%nx_QtMl_I-@bk8Ja$;TK03??JhVJPds}#3tWI?@DX-Cu<{zK) z^~X*f5E!guHNKdwa6(4A(|aQkq23I(@o_T`E!z48#6dTEtUYOQ=v-QglM|9)x)qh% z!{^T9WP$^*1cD~F6Wn}*AW^%UV+fa}A0M)&unXIp}&V%}?qT`#c z75WWvUn3w|^)6^o*>$7YU+!92PXadZkF{KW)OQq=_6k^EG`8Vu@!}p{OO8%I^W#EQ z-@=y`&fDUz0jE(~UHj7-O->IG1Yn}n`1I0!g`k`3V>)4*?aa+Cha^8He5HD3t3j@Z zz$!#bzJvEbSUFI;x?J%E{4DDGdd*1C8+7SFiq z`X#4{OVqo>25xp|nz5U&_E4$>pQA$z9_5~3C^H70qq8A?xuw_0lXL-&*Vsu_oU*6u z!L=4|6h7geDAy@`>Z@-Rlzsd@(%1=G3voP{;^xqO%#_R#KHhh5JeMg-a=_J3rviu} zYjKwWfb6`oC~LYuqo&eHG7;k}fXu4}m%W@!`Y-;iH_u|wG121o24Vu6cUS^k+WQoa zj!D^FlyX00c|H}JYQ3LZzyA*JpD1g6Mw)HxC^(sG%xt?riC(`C+G>1>O5pY-2SI6( zS}}^ecBz(n#f;U6&K*CZF?&;qbt9j53aVJ(lJ+atvF^+6YNT0A>7b$85hr9P5(_&I z@GQAXlNWhe@LnE>R(DYnrh$T_r*~L=chKdsUf9_EUWl37Zv-5wbm?j>S82Ei5`Q(` z^1v`PiYE3ctJa=_b#6Mh)_NS8p%0Wyx*c6*swriqJY8L)l8g0T%*$@JW?RYi70amu zOPGrl>viEPZ66R~he_B>vcBK3nZAcF7Q{l{bn|w@H2Tx%9?nx*tUzMf)>LYIT>oWF z+GrX}7*QHtY8Gph))oybvu6|ZW@Gekh98riJ)sorhm+Z`QNynAUFEY8lxwa7_O^^8a;Ck(xE~&G4$UNRi z*2t_QU~^Fv%2rE;7s_@#&nY=mcIVYNulxrN?S+oz=zJcw^=*IByf`i)ufnSXH$u~1 zKR`FN`uN_vTIWnb0iwQ}?m^B-y z{)L?r86stPI<1$qe|cc%?CiK>N9%2Q;(hR{C&O!Ms_X7sRE{2P^?P`&!JHktJMmyQ z3?|pzZf;CBUAqhR9G?Sh!NaVpW;C2?YBFUBhMS$6!^<_IouoG})0~IDU_0%d*>gGY z_QK6bJPxDG+IU`Ei{;aX5KAy4N!Sy~ky`#V8en@~9?7MQA6w<5i|Op6v(r$-m&T&z zi{@LIgwxPb1z&y9h;O%Kg^p;{Sl3}0+l4hIW={T?Nm`0vxckUjk_0vb5) zT$g0F-hCiA@mAc*BC~3`Cbc+yjteGPhaB8D>iXTH1BuBX`#pYJEA0k6UWX_O29N$e zAqpFZWYOd-!Cca-KgDQpNaw>s|Ki&&&50qqZ+4;hZLd6?(l$Q^F0Vf)O(VEtIJ`vV z&M$Z8u_U#-#qbw34$dl00aM&(S+BCV%Y^I#U|c22`3AR=-?0rnlaI`KGg(>Z1rQ`_ ze--3V3c5jxt`y_l?|OqAPDMn~EY7xJG&FT}td(AyFg-7rlr6eBPT*`Dji8+&N8Kq? zSL^U8|J6N8Pb1X*z_}UXh)Plk8@A$HH_L$dGMMV&I zDiQ@=D!sI7YCTg6`QZ_lJqenWpR6#tjb3lt2@$ zP9x4c8_1weqyN!S5`%tQY#%zo`N{I>+0-L+6p@b7RN0AgSObj$T3KwB6lo$AOy+v6 zMge?!=GRSSaub9TE2CDUGF*OL>-8cr=P+#6v*gou6Zp<&(R>6h&s!&n^U4Lo@}zR{Kw`eiP*-MDh}L3TY^-<0jyp2qgs+Ovdk z(950bRFFFnY83$T+r^pB_Un_V6gY3*{WVWAkUZr&YUAR*; zjdQ=hCgXu#pb(!v^$yt>sJdRr(pUQ^^aaJx@%zLenUzeUNEp@z8?&Z|hTF-8GQP{; zO-&5Ns*5-s+K*5yZ9b>_;NH3YcfU2$`;y%ZA^RS{8}VlayNK7KV*jXd{P?_7e=5l;~)I)iHfcy8z&tg4SIZ_Hl zgSqwrd+`)IZ!o&^Cr2(eIK$|z_VFn-t=t|bQ9+|#UT>Kh zHTw=n+-to}=t!=!3?;jyqXB%1dRv$ZnVllDL(>3yo}OsZueQ4GsaNGUKkcu$)OQ^| zdwmtqx`Vd8tl_SCJo&77T=DDQt?GKhJg0PTkRIr%~EGeidy$)_R*~SO~X09EL&$?HWfiRq*gPbHIow> zvG5ZdQZM^!NGDbPq+8dS0G80|66Ipw;bQ*@eN9JJZtx#4X+Ek8I(30NL2^4sau5WV z@bq|?*?JKhaU;09GUi~}bR7hUb3d5FJE#`e7`(v(C!hUoaM=S# z_P4H2JHA+4XL|QejuChtf#XB}O8Jio6LKOm?7UCj zv5n0>Mhc(s6I+Zrg&oxe&3ELT?c4zTE(vzpn}w}2+ry%4V}yY|G#k>EYFwbLO2#_Q zkP#9d1QAg7?6+yTMW7}%udeqTZ;~Qdvi+Fi{5mpS)*ybNfg7pys=!3#jZ>a_xgZFOw!^z8B=t&2hYRbtsf$=V)0XpZu586!-aUZ{e}%j^+7l|bHN__K6Ua(64oId zE(f60s;A(of)~x;q6viJ+m9TTJ(x-dNdv!pEgtm?7`j+9U0Xi%uv>KdxN{1$fV^79 z`s#GKKt!*YS#or1bq(O@OJ@8~q30UPsnx1gZyb>chCPXYf!a)}=tE)r**Q1J7dc)5 zpjv&S%>_^-5ocH(xyjzT&1bYpw7Mv1Bcb^`IU@cLtu$sf_N}*|d;6tQExC!*;ThJg z)b#A}$V;cuPwWvyL=ad-Bi?|V=`dpFlp@L?xJEofJ=X2#PM4xE!n4LVgcOuNR}3O=z^THh+wg?GV!Y1y~cQmSpVtC zOD+QrCfc7)6YvCEwFk2l%K8Pn97wJwGPx+)%J0r~)kVz2;yX|>fn%j)KjVDo>c;GP zV^gv47^&%l8R&69G~14HC%g99V(3ui&Y_mqf%;J00Dps?9>Me;>G;wr4c@WD4R~svoMvECd@C(FTdo{*5qt_waGb;%Ye8Cx* z@EIKXqFCDLk&+H^FDj}#h3~RmX$T~YKdF86HP)ib(s75O?=MguRQbtW%_^3)JhDd2 zod6lCkjT3xQ)iJkjW@$kBYLeHaBzrZGq$5=3|i!SqGFoiLph}#XWzCo1PgYS+|~3S zll_+lJW6#;&}0(Lv|||~|NKSG?=iL{&5)C^Ho(%*&D}miQCoe?Mo9ZV6~z|yJjFKd zfcUaGA)Rz#v9WW3C@4l8i=km3I}358q)&dwe<%m3`Fs}z7F{s=iYoV@0Bj!he~ef*h&BlQnrvxXgcDkHh(sL>lO3RLtc8ZM^q4aduqRUvA=C0&;XDH7}7tu9Hp z;x|kNSgkjyrhtlOj}^PAk5jLUUwm;c*2XuFVTVKdjVWWT5eu%R@jh?sk9a*IqcYwN zjx5Q{b#pR6ff?KeUO5B?z6l_Tp+3k2yVI~7jY8&7lT$4r$oq8wa^ZCCz&|QWZu#=2 ze4E|4`)gGwM4|&MW|vf9baJGe0bxDGY|taQVsp9VK~stQH|B^)Htz?Rn~obE+=h*& zr;OKWrI|*LNcYU?4)xYK88Uk|@kZJ9JWR@!nw>q$<_#l6Boi(8Z$4iTC=W{sAefJc>e73SeB$t^w{&VALf4Q23vc;u9 zQG}jVZ6UxVIYZAm=Yc{W6$fa3mo+RGc+Oy71x($R9{=}lXbj&+@t*_ z71u74sogkVh3psHkFCU&#L2tL?gV zS33G6vPaDm^lVErMOXw^3c$1hTFi`_(EVcCza_tdS$n^Vt4&g4dZW6vq z3&GFv7W=v-Iiq_U3J-1tBwUjUzPu^|7G3pYTOu<5FV!0!&&^k`T|rpi4L2U~a@Nnk z4O9|TcsKwBOGm=44Wq#RKHT*V$`mq$f>M^jvGyEae$$cLaE?}D|0D(7(g0MxC@FB^ ze3})uCM+l-WNPOny>}i$MI$=hz#SfmpN zi7-npSze73KNj8?zn>bPl#L#@fvw=D0Zp?9-yLne|JE-YH76TVow1Ja3gQ~G zO>`bVbPD}%JM;wBe<+k>XnLE?(6m_g|GXcwT3q+bKp1R?Uukdy0eS#hMmp1Vg!HW6 z7%+>47-Xcbh~U`BJtb&-%eIjPXAiL8feRcJP+9<{+3JYEGbW zzhq|YiL(2?04&PAwE3ADg+w6lZ1m=ct~I35kKud+tv8LaS6i+(L@N}l78mD(OpI_q znQdFw23{i__=?;shCd&EKyW1B8x{aORd&0F0Ce+1!%l=uE#Ir#yfK>Gc+;mfDM386 zRFg#sta2=Tra>vM{<*u2ao2>M_$)RV2A|ky%jWX&4-$#sz z{k#kKMgq6uq2?gl_?PfSmT}m zUCgGssm%l8Z{-OnCkmBkZf;!@vu`!99Wqx}%=S-cuT&**l7Lq_7ASE-qD1E9|I4@L z{$E8~GVVn5|5dbwEXtrt|6QrWPZQ8!GU)P0cvTKoG}7YlD0)JoOI~v0E=kw|?R{D& z%OHHbR1Gw&9Dxm8aa2JPf4CSD17i*I89$0d(Le>jvO=Go$nz}u+kW2JgiS5~;d?N) zFQQSvlL##d8|?^KOl=Q0L;qM~IZ2^jId0MS3udcbAG{JIt5r``9#+(h3*BZKp?1HM zaaL!bwt(TPGkS(Ns$zIfxV^D?4YgBeV2)APZtgHiowVQ?7-m*>J$g5AV6Oy)e}t8s z4lBEx0Z)|F-BbL-%M)i-^M9S=eBBk?Qo6zmKM*L`yhH);eaUi%Q@GCCD?{$sP`)Uh z4eQvTq92R9C~+Gzl-0@aiMYs-P*4q=hdHa{kOgb|xC@n;P3 z;G00(FHPb7OGpIF=rrY+c7_bEiVeNTKIZef04=;&ALy%`N)KorzA*iIxy6jm?qE(j z4#PNJbbsCTRTBZ8q_0T zzx97!KdKQ%eGd!_9${k!Qw0C{Noy-izF^Dc?_V*+T3#m@S~~dNU$ndMW?B1_=W>fY z?lG@Rk?8IxmxHBBfoAEv_fx12a{HG;S2ETtTU^9v}*4u^br> zL);-&I*fza0O|dnR1j-a+SYU`t9@bSrSb6DkQ@M;Zyh+qADg5DZQ1( z?aBtBk)tRupiyVuzi>wF84-@j$UN5YbWkAHZnk!Ue4UgzAgctd7Ma-pnt?cf=t&Z9 zx$TT-rAeEox_nj@d?x#s1Ne`rzyjsJ;|8SDfW6;R{YJ8>A#1W1X&|qU1(IfLrhidA zU5JH3-1zqv%J}qJ+<>+ z9)D9lj9QyOF|fd{vnTHUiqm^g#B65r4tl!%)AtTJxve(-gY1P?t0xKQ%Y0m?3u807 zMqHyKWBJEQN{4e^bw(}4lPOn3=umoTeOw$#iL1S3++Q;ye2Pco*7h(nC)tUTGWV>; z=yxX@E(>m*;aj31E+K8Ek2NWB{>9}!!lQ_FllzYi`*q}be zYxc%&sc56pTJ~E5C(ijQn%y*JJ!4YCDvh%DCQ`J)eP{wVnTprBiNflAe8CjN9^@Ry z%6@V7$E|CY`=h85uC@*Mxfu2JYf9-Oo^N&!(aI`5S$MkwMfulglF@o4Ql4Z8Ynl1% zhIX{BM{hR!&4R99hHE|dq8>zt_ZlapT+n!;M(3!)yZbw0W<||qp6v1*RU<3j2W!#t zcZp_dsxH}I#-rCfnyi)XN+<6RO&`70*m%o)-k=2GeISzbPy-uHu`z(PqyL~cyp zFEQ1*?C6P2Cbw>c`-J=lF;UCY^;k4#Ent7volwsUD}LD}Bsxo4VPD8tgs)7M29GpO zDwI<}K>?SxUbR+0{fDegi~EU4|K5gNMrv2$`FLVpFTNoqQm`bW=cNqHmBevjfX zAEGq5iOlYq^QmViyflzKae-%%iCc^~?6c1&g|0f>FcE;alN0LiF)hlx{3O+X#^G%N z6t$HIKAU1wSxS&x`X#%xUt#3=ab5iXyD+O|o9OE+vTCYKK=MJx%)R;jOjTS*NzNKp zI7bK1v}RR4XUp4B>b?~2O{1_hiTunl7&>bzR?UX{*Q$GBRp?vF$0)ylc$NesIgk)a$eIDeTFmIj;{Blw`FZJE%y$;wb5#KVTYnO z{IuRshf}FDuF0IlM{P4`$pYVvL?NFl# zat3?!4;2IwVOhDw8{`8d=?EsaNxm=53sBiQ-mzJ(DT-pmj{SM?PY}WeCSt3+VB1Al zNmG~nIeGWA`1(jvE!&d;{dY^mx-v!5qT?}MG^fmi0=Qc;LFgM3v8*FT@R?>l-qMgX z6T^X!1QuXy_E53#&_Troj)h_^n7@5FkFaz2|47KGu@(hY>2IV~((Pe7O?jbr6%xeR z4DHEDivh8Br?xsBw~r{@W_0tlN?wm9h3oFL%3I`;tJA7*DVKDRLP2^umo;P0FLgYVl(-#TmoVN!=cr-2)v5UMEmnYV*ed9pGLH3mpU`$^W2gGP@B`9-SY-g1*-X{r|D-j6}r zpBO1e6EkGESvom7OxQJg$vP^NGn!eWn#%9Sz}_Eee7}cKcT9^FQu}Y~T#92zCHsG~ z2L9Mm1|b)?Vs{NFM}!2BonSprvHjyN$ypUmpJ_U@3%pV^(9ODpHv|Nv1g27+z6cOk zgAf?yf0}LG5PVs8?dbHjo@_QkzWMjw5)nAh%PG*Rs$Loy1OFkrnxMBhxF6+QJl=36 zd?=p`{_4>4*QR&R?DOEf+)ww+LY=^9|{^jL}lP)g`^90{$u6$&&PU~%6<`V zONO{)N4ZzLo^E@i{`2dGqV}K4KiZlul9Vqb)`pDTJq+nIB&`(bXf_-2L#NmtR-?8% zI@5H?uRb~?UE9S+SCe~bMFX-LT{gTdXOUf=r_dYToKN*qnO~m{N9s=x9dSlp%nR&{ z7Gd)^-LnpmWGm^s1RmT=0?IoT#aHd#A^x@A@Q)$o%#hL}`i|#g)EO6Y%@n!9GEREt z55hY_+Kpi}VBX-XW%TXlYb^Ek{QD&W{G40=scEv>^38XL*qNpplV&c$S*TceY~%hJ zIW9hqw0Sh>dbo)1;`Gsic_nXq#?JcGTXHrkhmPk7^zh@8w5!Kpd|MA80~+DjMk-Q3 zC~9)vY9Yve4z>?i|GoZ)D2w$S znV=%HgEy{Fbd-OW*~d4ClVH&R62U)9=D0mdMq7H9iIhYJ`MHA^J>%Ckx5;-@)-utt z6|Y(E*h!n$HL3n+HPUt?9~n)OmVy^7=5$!3kB15;hcqiy_%P5C z)`OHSy38?>D0loZC!L+c2Ltgpoa&@Q$;;#cbW_Y1iA`L+byl)2hYilf zYlEd86cpNcI9WoLYBnIKl!ps`UK|dB3^74}mvV?>8Tq>udmuON1jZa31DpcZbDP{p z8BU$C$|;VRs^5!cldz{PrctIPfRgXFO5mH@R&6XsfZAzEHj`~y^XSaqZC30=DO{Oa zc#`allv!?*(zoGn2v3k_o+TbLXKs1Q&TuE8Sia7Q*|h;JXh6)9DjMA)h*+}Wf61L1 z|MvUsSi!5P74e|2|NViZ#LVwyY#1CzG~G3cCaK~6+D>FM2-kAXBo37=jrGS>YP~U2 z8wo7j^2z5`3rRF3FDMoqQPh6K( zXg)Hvx>o>g`uMh)^(E(8p%q#kagRj^Cb2E}@dL?_RzviM2)Nd{Ta}CV2N3%FV2`Z^ z-1r|C9iHuT_LIO5WJsn;InQ=OIjjG>eNowz}dmiwZ?<$Iw<)1xVv0^$Jxvaw@gr9%>>oPb);I}ODz z)UNKdpochsQRCsQsLZ%G(?p1d(hXe^u+!MD&*Yu8U}4>cDwg`{uFxtp8qnD@iPy-Z z<{tdyszF-;l~WVL_2JdtUlT}mEJrqQcK~bO4MH}e+>7VMN!eBsAzcr<&5~X)PxCNyK(*30DAaqYvcYH`?) zo_VdPl7JkB3vIN_^x)No_%qw0lsP0vCw!ckDtXb(AdklBe8CrY<^QFjbk_zT0C=`p zHqEIvoFfkSueKrr(Z0S}w||WRS{ir@wBY8jM)ItT7Rn-y=*Mn%_=i~WgL+g{=xoC=@ z1WL7bZKUhq&l&9gt&zY=%IQ%giCLTpHiXdP%n3m~DjCHT9h;(amDu@iKB}mDCA=$Z zL-=J>T@Uc0=hjWU7NOUlTE|BD7sbCE*_1oNdyb` zw)wBs3`#CXO~Q#kLF%rNqSXXUH{bya-6}PKV(*DRAU4p3UP1$w+~ik^H{?{`H_Q1FXA;=)VuqZRpd@r>eIaj=L1x>6>&}#*RTf=a(jIRb@2}S2Sv{d7fK1*YJPZU}zsn|2vQ^p9Yk?2^|Ep22Om< zo|c0hM}U6E2pPD8tb(c&8UbMh6%oJp$RcTeM=CfZ7Yy{qiUqu9wl+X?cgpc9`peT( zFsK{bZn&s5CvZY22+*%pYwYkA9XiK?SG?Vh7e?S_pbFienrq_*E%BI(<=a;uB9dcU z*&^C9b>S(@##iv7inxY(bF+jT>SKfENCvBy@S@Y2%_q*=)qQm!IIt@+RnL3TcjNqqFU^QxSj#(_Aq^*~aw@!kjjW@? z&@lH#%PtVbhBa98r+7L`2=aTt$H6tEK70**nB^6}TZ(Q;?j ze`wz0&mlt`34aKY(y&&jrO2s>DN0~xjn>?c-~&2Gz6V$HxNM@kX{;9Aj+$I28<4jg zqwaT<5!O2eW^AEhNA%>z^qU_?%Pc4KP%F~%-{E-uAX(J&@*gW1|Jks^;We>l)~dEM zzJy}S)ZDjmj}20K&}^9yeP`2=dwUB62>50oabnZ`xDPLlt-4f*DpdWIjhcb2?N=6M z={n^jrzxj>NiWFJL0_jG!EiZ4kH>4JH^^I=gVUZf<2IvC;X0}LB=W~g#%@q&>7{%W z&u&DcNW4FlTPy+t7qWt~-nQ#Cs7WW7g6uLJn)Ieah8!ymGp4EVW^V?ee@D zEjcsUvjVSfz3w(nPZhsu2WgiJ7pNA@%F328mOo;sWXumi_^o}4ZYr^;W(Y+RIsKXR zRQ6WOzXUwo7%k*>6=IY11+s1t<_IK@ZWKW6k6g@4m6|lo4QN3xhVj$1|7f z?$t>oZlJp^sqQxFQs!9lY5!u=Qi?98EMRpo9{c;0#Q(hif9?&3#@S(lfu7gO? zbiOq#CZ{zgGfAyva%58hBZuQ*2^EgkFDs^PCBL_-7lvUeE)z?3Z0ma&^^2|6#zNqw z^n2&?KF$k#%jDgStzn;6^)HYGt4(q{IpaFH*Cf2yvaPQi7FmDz%RRQ!nSCT>r`A|p zz$T^Ibat~3S5~XhoAWT)-gvg#+nIpTaQ2sm*7cOLtw0{(>I{`m-6-iwa>^7hYng$d ze&#K`+1C;(1y#=@fY~eoZF#d)-}#7IW|NRv&s(h7_4tsbPn8}0-$k!9FdhkSe zML#_fO?#akD)r2JF{N*H$9WQ`#a-Jb)KZk~lm+4nkrY4oqEcOvG3cY@a@AudO-0Mu zhm>6rsaMz{k#g^mpR?5G_2k1|VZ%X;#8#NZAtfWHys}&NtJ~J*t>e%220+edCVE7- zd+xPTUP3f_;I`_+?a-e0BkSG0$%O`<8ET=b8X!QGZ@SS2cz<=&|F^@3h}H5vQBMd9 z$OIKqi~+mT5=D@*U{%Q|V+n2I35!UWds;#&w=*szMBYq)34lP<<8^2Wsa$Rx5X6uX zeh9|#)>7W}ySRft#O^3a<0_mVc2PMs z`Tf_tcVRfNvmDzK$ce9i^q>n_k*=>jR1%Bmo+hgH47b)LVxhl%N>v8{IeIKGVhtCDbSf5Qa{rXF;Ol3S3 zX`%sry&FAgY_^28QxdG)j0uZ9Ko*ldF>{QZ{_Pr*G+sB1gsBh~pCeS77=;2=W63%J z<4=9GU;t*5jH`>&S^wCiTMIB+(S~iU?0Wj-aGLUw@`Of3V!|vr1d8a#&`n zS(45K@_6EI9gVNK>+go{TFmvWz@GUtNDDr?98#2 zUIfA|H?08%t_{2ANS+?k$>!rDmP?T?vDUgP(%i_KDBPdYF;o`*EDY}cg@>QSt)d3~ zzBxRC|5dN>c7YmeR=2S989AxsRAyJ#aP1-@^=5^y4Gw>;?|aVpv9t4AA9~8!^TP=A z=E+vy+m#OD*BBT!(LS;OI%RWQ@kWmH$tK4$urS;yfArnJTGOkE$#j*}Z1U!_X*@ET zzD6{}TA9xNkTD1_M{3oEE|I;g@(otngMmsAQNp!6uzEhc1#iCmzUQ~<~kGn>+ z6xjD3m$Rfw$qA0^6)}O6#_`6%P6x2sQ#1i4l;kGCvd{AU;Y~-6*aWj~RGdeiUrl8vFdP4f8o;NnuUU{sV+TPXVk3& z=*ec-IxHWHuJ@|DN?DEI*uAB5#xrjR^A#EG9=zUc9#`~?bdfor7-;R>@!X9p8%vd^ zBoH$bV17~|xxPpozW9n$$c=+%O36wQIg`rbNj1RQB+KXNelYs2il1oCi>2Tm(_-{D zP9!Nf)JgP#&DTS*ACshO8v!x|D58jPYp2;#GX%o43QAa9x2cL_NQOqktmMWBN9#t7 zQ3ZChL2@)%dtEaC$cqV{o>6+6iloL72;TL>Zv2ZUIF<(%GD6V+-`@K)n@eb^H0D76DzrS=j3mxqk3tugzRhsmheNm zmWT^LA61oJevl{}xNPKdQB6Hfg*8uQcq?%ZqA|_)XMd#f6|5%Di1KZK@s^VIU zGI+`|AnWjCzw(ruv#jW{gTkU_0fJ9?YW+a?)x&U=ipL}J?Cyz*&kmCV^HQ*)5WrV} ze2;^x?iJT)F>OVI*z17!1udn4jUN~IS+UuQo3UyyJ+3KqrR~ypWdk0lRwatvwo+6a zO4>5>;h-ywVzCvUf>MV^IfWBtpL2AXabKa?F-f(xTmSHk93{vp+5ofP_#MQLMl3-j zrjU?VLN-e4hu2RUKrQdWQlV(ZV3{u1odCe39M> zBX8sixCCpX(~f>>==F-CyDX9O@;Qmv5AdhqU_JI>(ztrR(}2J-w7ISgfq-=f@)eJ>p|vK z(6Cu_zu!>+3`d@erkm?IUP^Yzn=OSyi7nk>h@;S;a3$p zi311J%@umh=__WPYogYZ{JR*v$tN`EXfgv0?xwx*+!Z_ z_yPK4a;2<<8FL~YN>p~6Dw<6mAH+YDEE>!R&6c&QW%s?nK$y`-VG?jhE9H9^;T&dPc7N!beq z8P9%V=W?ZA#oLmKil$(q4SX;9US02Jq?S#8#hlcYN}dKfhkU8aFP>US4`hTX3!`LK z`pSX0n-O&;6}C+%vS;;}5m=4-3=Pm;_p+gx==Jlq)wbu9yt+$lTc;-$16)`=^Y~+EOsiTl;g51w9DGYkE^ww;nQAeW#ALk> zz^8?J60!XR@dgZk8}}iaGefoF4`wZ1NA1TV9SYa5Ilz&Z5|LN0yw)*eTv_!~a%d<~vWdgeZ*0UubvJ`;v%kT^`%_+_W^1%DM7qm1) zQeTUWd_xn5?_eJ=w)%SrsqgH9`K%=8_Ao}UE9QmCuE+234)T1w%Y4@;_$VcBRK#$> z#jrZqZ$_fo>X-zGOX+0GIZ6VVn(hAL^+QZ>L>QK8+$MSFnAW;l%t&AxO*YA#V`;z! z4Q74O6aORz51+T%r&6OGVRh&-Mry65#g}r1OMj!=z$Ofm;W3cH((E4b5|DRYoPWG5 zfUcQ-q^%oXeniJR(gh!JhKKV@GCP-E5J3jQ)U0#r>H)2vdVj&@Un!;$Fu46qty$ zb$%5_$-|P)QX98d$`VP8#N~s^rOM*aarFrX9Ct1}A^t$nxpNkVUE20Y#5pgR!ak>v zl@nC$fRRU2=A_lb>h%`)2PQd~MdXvQw)*N|+`$Mw2YB;rKW0(KJz(>KOqroFCF>Ex zef^Eg!JH;XT(9PqDb$=Z@ICPgvf`m>F;ZA==iVWKA_mRl(9-f5UtNl)Per&IVi1*t=L z8+&=7`>sP`?ZCkkCOlR=o+}T=5Hkz%VDF;DFF0pw2m1lhyXCSbKBC9#~QkVdW+LYa#)2==;1XItb1f zk}MO|0T2Ps&dun%P=BVB5sT%Yz#}nO`RPy;dVfVI{+I8o|H?-&#s5i|3+ll)QZCe5L6B;xl(IeA|!aN-lR=NpP-Y4=kkn$VW{dj)D2jygydd~OXwOYAF6|bC+6Q9 z0;8e}n0|NA;&(mx8V#4RKMg{B2HqIk&5NR(a!1sAQ%RGvrA9=c6dD<^8#~c(NJVYl z|A4)LD|qjuL<%;)BuUim=5;_apA`xuGGjbFlp`gXEmHLvoLA@}YanvS(F; ziuUl#>CF1Ta$L7~*%S8b|8E; zG9Ev-0+SK`)LHSjmYQwn_Vjn-N9(~%ly$V;%ux8Idl-!vc~e> zI^*vjAXENQp+@TS)qI=F+&#WW8N}=G#QYcqUDxmSa!MUfcD6RgH2G1cbPtbhlW<}i zNjZoIK6&>Zhg3v1)@h|X=n*IDPvQW~cn*y91E3>?lSFr_p+9L!V3wnTi!Z7E;>g7? zC&L(7$arm{_VRRrw9NMT>i`%sC+Fx&e0W?qJNpDpoL#qHUrv-W1AC5k#&h z7g#bGl;DuHe&3g&xFoY%yW<)jCR5UWsrhyLSgViYc!!Jc<2%d|8)c2Xb-#_3M-}oB ziRu^qNG@t@fBukE@R*)a0j`GWb*-Rsnf27;BUjJ(!0$O7YFeK&SB~s+G%K1*CxTfE zPH(8gudIdaq(qDQ7h(Cwx18{$R|H%ayI-ZAZrb zd>M~_E4q;z#2_D)U}&%2i5+ahZZJc@9vq>+(Z#ugMmiGS%bqNv{{eD+I)d!~$PWBU zqx=wMFt%*64{X36`o|c@CNOAjsfwmJP#p)VOQx468 zaz*~CRzf*84c+H1@b!B3_Gtj!$5-zKx8o`3_3p6qtan%MZ2r_c$4Uxrp;K?Plt;DN zTt-++wHz=z9Jys`tv`F=Y{W87WjjPa$EYO*?cpkSV@Mmbh2a=m4>j6ZgJ(w^U?D4s z*9(>lF$w(-xX9{_`k2;~t*|XAdy^#rN03A;w4oxsT>oTLt+>2R!F`)6td!X?{{SnP zfmun(C6lTj|BIkUY;I58%*^suSFG}%Uplc(k}LbPe^gcqo3{8RoYCpZ-3Ot0JiI^c z@f&nQs=sM;1RlIYLi;#ih}us?BB7)%=uYhVL)|%UbJtdOJ~Ij1lBBo^+9(-?HP3}wvI zH|ETx*el=F7L7uws3(8gups~|8@=GDj|+{Ybx_p2`LxgZqoT0UNUY-#bH_K8XR7pc z|H;w~q=tN~;wWmEIa=M$bkv|kebH%M-~UQs9J)0aTJ|TaV`Q==4QJkKDDwiHj+bJ# zfoG)IGb8-n z;@LTBPcI}W?JDKo-7Wk4A|bwPPxF1YgPDab3R#; zgV1TmwW7ylg1d9fqeRF{pu!cN+kKoby7bE{Tun`P-=C*dPO2!w<}`X_4nSgi&$j;y z??n24%?&27Q&$eyikg}4aabJ3xl*&flAhB>o>2O|haxI$!x#;ceg1mlQ^@c?2c@DikXe=gjE0UEMpFiFHt+qp5ssqK{>T;)Ds?`}^ z6LD|t)Op;~UnEr;uUw45_6U(G$e@_l6PF9T%B0}Uol13y@nNnlW<8iZgo}l&{sIkm z3Of`{*0T)y+yHP{9hW;;&Y*h-K6_!XRr=u`dr=yWqo%VK@=bKxJ?f91*|3F{N8md| z1@57a+L2#mokOuxmm~t-!NUNaFLcd)Csd| zv5PJICs_!6q8pv$Nc-9M@97T|lr$Yx73S=l3S%$oT))7e4cCu{1l%Xoe2zB1I}@rW z)N^z5ABh+Mo(EU8yK;slKORx$>XTAU6MBp_>@a#WX)|(Fu-e74U)bl~M z5b>E2hP$Y?o}8;6hud5EmE2yyy~9$w-hy2mKRm6$dKW$@z@TZ1%)k28JxVBEFD4+c z>kXS)77^@zR)qmmr?h8UG!m4C?w$Ek>^bAGqgi9Kiihd%(1V&mn8p3N1^hILWuBKT%;>*BMSG$BfRe(ON6R6s8n6#q0bvf7H)KiJ?F3)*7`|{73jhKQ*5p6WtB-lT|EW;_W z7MfEpVXRhgO-#br@)a7CCzpB8y-C|K`ZwYpg`6{#ux?fVpd6IU|LB$Z>cxEe-FbLu z2~zqbR6f4ieK7X;w*>^t@unZtZO>RYSC)}Jka3bTH8gC+u*m#ocJ^y@PEHKKq0yR` zC?qvP?c$K{$q<-8{YN!R|21dR>hCYPPPnP&oysO&>O5p=s;|TWMV+{MI-C^(D1iNg zUI&LL|Nf#hBZFBPv?Lz8uO1-c#v}~PRniPqWP4R=S$p%A&%_EM4QYYIbVP;!a0Pq$t74iZ@B>W~!d6&#({>hOR zb&W6deiM=1=jhE2YF6JarIhkjyth6WO@g7aUPYumwD!O^g)I<6y|U4#_QpJ)d7VmqGN zqu1#*`uZ@f_H-S+dQL9lg)HLTOD=N%8!^(f+5Q4&HaOhvb(=>cDFf2d#%08$r7#CP zjqNldBv#$2qp&1}**0KT-JX1K;IQ`#TP77WJOaUO%L!Y%Ms@s_sP`k^@Rq5KV8~9{ z)wJ)g3SJ>RG}BzX>7k@p$uk|;fYxi8-RF5eUDvpSP1=%DAzI}2sRP+Rum)V_TIIWC zrOc8mueL*=4x%F4tt-Qa=>4#Tsi2r_x6u|1KgJ&y+P3u8@CIxv3tsBF^r#FoJ$7`T36q1WV*iO0BJvi`$Q3qa_Lb8E)>* ziF>qS5$vz*sUu)@VFrkpTmgEQv9Im$jkIx+-}2?Hzp_SqgP#zkVf7O` zF*;9m-3Cc3^^KbLmeRe1;B(J8`iFr}v-4IV-!}0@tEp4;wb&7qiNhFJ>NY3n8oxt; z`8#BfVdKi0K4}+qu=Df_nqUj&y0SY);75q^FZXbr0flZND6h zvgTOcWOO=t!Q3Eau%VkwPtiY}PWAEd=XPb{By7ysVxr8e)ZL^-S3#?LKgCb^XDj*3 z;(*k2p0(h!z~|{IaUg=r!FY^~KOvMOvOY6U`j9JN5@r*HR?(*TKX7>W!72mca0C)n z3YYn3M_RPq=1_5W?atlZW5re1FJ@vT?>=%Y2DF;K%KYiuN43PiNwnEzYMTFBDpX} zxT$d_!4N(v;s@)r$|y<>&N_epX?8zE;!UmT!nmx!@@IAwyN> zu%X@N0x2di6Ffqm7fn{y`JN^CjbHmaH}j*fchll`(GXZ@H2LM0n9w{!l#-X70BS)n zubP(Vq;GrM^}$HFMtj)x;e|%i9_a<1b!^_*T-EYW(2+H4UlFyu%`l`>6Vg_GI|$Kb zX2P$v=m-9D1TN1oS8ac9F~_V+DFtQHz4$29g7%5#OW4gMG~&=&|9ckv6!6Bd{}H*k zLO?WVI)OYc6eM_-Nm;j?D8UJ3AT|V;q}OT4vdt`Xni9qEfC?$c7ZVmi$bE< z`6R|@5D-X>fiwhiaQl7Q*&20%ksxaGHJ6|FxZtEG}kZdF|*H_!;Ys8m<{PalC31+FbhG;aB zR01|%WVeoZ<)P4z4%`W6FTnTpNGCE5+W+ z_!aT|ri4%|d`3OEVnt~dC4(nAoOv^rzD;pZXZpg-fN6`dzNA2o@~5nUy<&VlC`Xe^|tp-ryt#R>NinPIV#Ap6G;k-vTJEc21o?+d6;B5PooXA=7qI*_31Ck_wVJzDPCSFiz1m<&~}aU7s}Go(vmMC z3g-VL!6-P~ozd|v^k?Q`AJLWU+D)3@;HGcs!@5tnt4e+SQRz7oDTWWQx3r|3NjYMmxgeqlikc_*}JM@owAs zRn^-~pmlS7Eg~%(A8OMfKj{EPkn2Er`z%2`ZOCS3v`%A`sbNXOJ0Te(;{hV_zlu_E z;MD!Ss3%4pE+|r><00!Nz1xbIY_@GHc1*Q0z4UojoR$`hAw&IbD^ohi04LTTj^FC1 z4!{a8E>C=af+k%-2Gi-3Kq@N}His++it0SF*6y-`uL#GQy#L`CB*P3GtjrYx@xk&2 z7K?HwMxy{p80A$l3o`n{F-6D&?Gij{Y_s!bCjt}2K;eNkbA+JZ5x}0z;SnLY<#JGr zme08_UijwC>y^wm(O;5?m!AnM@h<+~; ztv}_AfrCAK!6#hvdo1ywHo2X>`4sMb=gh2U`l{EHTSgBp&5m>9#1neG`BuKHLgc9ij2QI z_PL0+smix~>VesOHEIKJw4gSA;x%=lFC;#dNyS@=y%PhElBo37S~TE&YEA0fn)iX2 zON~^439wPdJvgofNb;qfS?czf!Ak!&$07=cT&fB+uHP``%G(Nd{??7!K8&A69WpV& zO~O0X)sY*1RMj*D4bwVeZiXcK)gAF`LJBkbKZA%rqsPvcJh2{ROccMXNu@%HKfuBI z)05dgbuCp@-T6fJSej{9d=pgP)>FA5d4rSQV`d%x<3Z3#6FK$GI|?|;x^kqlxoN8Q&)epdjyvF8P(8Q8Q1=d zv(Or@UgIrN)!rCNM(4jbpTo5hCuWX~_bvN-bZ4-Lw=T5!*>m!tWP9+dh^xpiVIrp& znk%@U8TpOWjqjc~i{E|zc7d#jOB7w$d=k+?A5e>$n!Ypt@kspR9+s&1$s11e?t91wDd*oBi>5IXIX}&}%!J!@>F0}+7F#qd z1Wa<7xECdYr`RYWZs-i04oJjrg+s6Qp(&z5z#(xian&(8G-a^4tw@fHpnH&Yr^ z+#yEx6mAdt=_%78L)(@<$9+dP3IKE6K(y(2Qwb@e2PRrB_hk ze~QKvRm#7Pj9{j~e?Vr`7)R#dqhgA|Ug;+A_W&rP zl>5SrrWlu``BK;{PawQ3rO?th~ zPE;@7`4)wzr@tDD?69@en3v>3x~Mr;_$>9;xjJaho{II(`42XX=IA%M=Ra{M&UQdq zqp?_PsYV(crE6?EWbH!I-W#>SVI}+v66F_9LeCeRMT6y~|CvTM`Il)ti2-3HYHS|7 zbt1uVSpkrY5Axupw%~b(sfC_pu<7g3h@Tk?Lkd4mUY0Ka!x|9B;~O?n4sT}aEVQT? z8p%xi$DbK>Knbgzsp44*UW9+S!fZk@KL-RG#%3zU4Fm)`xDg8!TDtG~v#oA(cS+#Xz^LOwnb7F^tU zv7h2Y-r~T5Vn^c_3+BEi^T({c*%x}$oB(QlutV<~m<)qjM`AP zR582$*(`~Rz>+otweEvQh{eJcdkj$exfB?)$P^akr6p@!EA$L>2DqKR7+sM`nw*Ln z-R#Tn{2n(#u^C8)(;?((LXU@8^*3PWND%}BSFzYBA|^0?f7Z~E3=6yIhG6LaXclK| z5>3%%t4y!Efff0F`pGECYzpQIe=N>2T!J{x3)&=s(8dqGAVa&*J_w7_xY^;>(_xHe z>)>O;KMeoy|0r9T{}FlZZ#n<94?K%DgHfg8*%b%j5NXv&1f8cE6Z6-+zX9uM=jz@` z1{0u=sZx%e?>+mo9`tU(2x6~aDa&j6{%#1keTyb zG*#8>=J6T5$T3aV$znQCA(V7Kc_wt6)ML70=@Y-xvAmce`63uCU+TaP;g+m>t)sW# zkai06czLyVj<)jHp>Vox%gzhn>t&x~^_0U)iHGVREZ>h3h@=X)BVuGtM0#f+vNt-K z7P?rC1dPiVb)J8uP7t8`BHVYj}K*d^zUeUQDI>2r>b{nq`^*e!R6C>08x`P<8#}HP( zS&J(uJxT|-@EiV1Ed2cd)<)X5`Wzvd$@Wl`{jY9zQdpY^aRdSpGu-=qG|^Nv1~{0p zULR_x0jLpOM)kSV#M?P_2)4Fz9rU9wH08O=zwO>Wi){xGdDwDr+xjqOz7VVw09*Ij z+%?!9C3Bt8dzZQ?X$L2YXZBDmeodL~k!OSFwW6!S30V*sG&{fUJF;V&H^h<5Y$9yil+8^3_@k(Je`Vuc? zJb1Z1MlO=D8kyB+37};M&Jbh4p3MwnC{i1*2}xB%+F%&~e7O+ zKMO&t;vbg>4=F znSwsl=J;W@OOiP!u*2)EjmPQt^Aep)lc~ki^a@{Q47H8J4G%U!3nt ziWpV*d`5SJmu|co>-dwf;pnfHf0hq{Zy_&VoC4TTq6)Nr3ZR~u@_i?u`16N{zkl#} zEkKX7b%bd9sHPQJvDO?&mt#O`=gPf)kS)527tsm8AezT`>qUt))mP&x^$(+n_os89 z7jDw_UYEFW(t?_2&{IXh-yV`9REv zavDGW_a%=YCRMDpSla!rVNx%=TLdGXo*-Ouu_%&S8dvI<{zp0_uL8+c|G#$~^|JD` zeC~|L%0(0Hw!mT5u1}b3jeZ6v7a3^?}i6H9@%;5|UH244r59cHvOqsbyp7P3ZldkN-U39uhg4W_!_gF`}Z+f?A2O3qxa-AiG+kGn@fk5}dY*iO!l zU{tApTqmKeMdzF;wAHU{%+;^HQ0={jr(3HLA0CD;UjzkU*lERh_pwgeqgB#Z#UVl4 zBAOgn-bAU8*WYGOQY~E_aQO+PQxrEG-p_i9&w+gy_yh_T zM(of0XoWtzKd#I~Qcp<1Qx(tZ`^e63WJ106|8}sfv|h*Wi5DrfOYcvl!B%P^-;ZPt zx4QEi6^rVetRZB*dn>M=+dWJt8kTq;TvH_=XoODttTD_P2on|4(xFZs&foKFL6|59 z^GV*~2$PP|B9dswL&?nca(e_rO=Lsmp1WK(*8E-Tr2QldT4UW_Tt^EkLzNl*M@wpA z-Ro1Y=s;7rG{?y()IYFXmY7O|X zes9VhkXESI?gIp-Sd+VSCM+zh@YU_Mr7Rd+Hh!7&!5##ocJpdN43}B45pKx9zlFW_ zSF7-!5m8OnlzR!-zmYS@+RlY@HXcWrURIiQtdc|K9boQkB&)x8dCrbpAmpw|YchqC zOZ)5OfwuRT?jDm^J7XH)=}TRMNA%dEzhpz;G2p$)h|QcW`aHts-zJW@I+0+z1B3AxntAg#piM@{6Tz6*Yk%oy;@qP7WQ7nIOI+_^bjHFv&_f9QVQ+fe?(9RLzW-kOaTbGv`G6Mo`Mz7<|% z*+IP9t9$l5+t*dCL^8QfiuJ5#PrmK^us&_;e`l!ng#mQBIYPS81X2Z97)5U5hzB{H zDpa|U?oG7eS{o%T%w?FbHX`cqU*$<9iC&%XhloB8up7j20cb)^`TPCp5|LBPYD4Hu zMyhLdA_BLyBZ@o>vu*p64RW=wNab!7ge3Sg%ofXW<%vMqKYC3#%U7ijFBso<%*kiw zTh|SkPnV};2XY@&knn-}H%ZN2)J=)z5BuUhNZs0WsfdIo0}xP&&d>6q?OxwqyA?w> zXMD=3#|~WchXB@Q3)Q4LORgr;tGW?{i;90%ijsLPc$L9Xy$;Kt%E9PhlPA`rE2&LR zgSX7sMH|ACB+)XeyeY|RMg~!J6->-%QB8{i8`icEIa=DCW?qi5x!5;At+ynMAM7{{ zgX-AoRz_1!%%Y+j*qBxEniiu5#+?|2Qm=EAdwuK8XTpM_=Qk%k(9ipx6))^oq?)S6 zGrF1oBo`@t!TA`tVX9=9x#2^o)04pr3mC$p-l4+@v#?lt?EEFF0Q;?r~UE0Y?JA1Us8k3p$(gA zV3ETufKEI}(csDr8!XQ`uNfD)XWJL!4It#SW2Fj0H(73ClbgsI{#GOJQ;!=@qs}_p z6IH@(qMoMMXJVw6E``!1wCyRDqq4Jnd@>=ty~)6`B}b1)UCGq{(Kvhwm>O0y@KD1E&#Z*NmK81 zXF2r#+rRUScxSQ%*Rfn54C%zQ`U@$I>{emAZX7sk=6$I{_1zGJeTWGovHIT~1ly_F zM(H2Vxpl0h^@Ca+xeQKwuOIK+{CQV*)VWWk4K{CcJUd+8Wmzxu)220Et_M}LweJ9- zn)mO>E744@AHL01$^vH9DBG(fGP(ON8k#yFJOP&r;18-^_`QgFfg$zE>i1rphko&H zirSZm8-gQx_Yps+V8`>TUp*R+rFT`W&F6nkG-4kMI2S3;3t#OCskb>vP5N|UAfS?m zchoR#%4tu6(tTs69SQylLVi7})i`@0ArDX|tB->xX3~%l&``(?7^Bj@o(coZmkd5J zEnOAbPe*ZDO^8_<&*#5v)>~bDu}&41%#(~XTde0BOZ|mfJ$V%BQtweq%tU@FS{K|h zxi*Q%S+SZ*gSuT4>Hc(1>%MUwG~-iCc%5Y?S|_zMS!e)kao+1$dub=68Xo`qLor9h z1s>r6P?OI3aU`_2hMmB#qFd>xD5B5)!Y#c>uHQK9eIv~dulmB8)oFI9JF|<6+u{D@cV6~^m9RJX0AD1y%EUW9%?)#FU;hR=v>U4G8Y0p8Mj^A+`m8})02%Pk zo2*#eM@;^^a z?EEzx>k{X6WDo1aDMxlN{tKJpd6E)o^t1BbaQud=@)FdiEP1|F&FA6fM0{0PC?p!4 zmW{dody{O$TwmKFrLH^$3kTOu74D@`xFFrutmPfN$L*@r_Uz9}GJc8e63bud&7u-A zd}c+POk1%0L(6j#;crj(j&X94Uf} zk)h&p1R{3q%0UGBMYg`66oyQbOkO#cUc)vHaml}|7HyLY#8gMz=DBW>Kky_l2}{=&hK~hV@(A0Jjq9Pi2?4nhpfVP z+<&4w(Kn8-fo`X17|_RuH{`Z|`-={F&JR*o+OD^Sg&$}_ARVYX?J7$e*D9YZ=L2gj zoIjOyCiG-96)y~ z02w?fc_FwQ%S7K~m@T!CR%n8Xj9V4z_m|^synqy-AU)c-WjgqGY(kCqSuVX4oP@2d(UO`9g}QuGyyKfEJguudO%!=FoCt zd7{P~ndd@I%ZZRgRHBPJY}As~>=N#?kf%hzG_8a%kxPzsZ)R%oe4D|eK;9mAQ8ysc zOubV^MOLI6Taml)9&l{FRQyhe-x;v?m2T%6aI^;(LC%pZ^FYOx!i!Wlgk8f*6y7i- zeZ(laVaA7NS{B-*L1YN9^34n6Vs=4m;^SSjF^vYbQ%z^ABpI26G_|l#521+w zk)KEzk?dTsmW0kgw>Xai8wY|&hyq@*!QST^Z5zp-(C=jw!ofY7%+PA=0(W?n?JtLT0;`F6uZ$&L> z%F@^l`@6#O+Tu`}c86yIaZ;7C{U!~la`|`d$1hB~;1rJKHajxrL?!ztN?h7XCHKmR z+Uad=5tZ%)?1Xft78x5Sik#Kp+LMaew$43c-78?wy-VF0`&GYvI(|G@fZZVdeV&w} zN#BQelF{tAofWJEB7va*sZeLCzQ&rp=(H{)|MTS3Lx7Ft=r37f8ae0gKGru>j0#uPs zv-WJKOFnIsI)AQIuQ)sgEm76GbBP3OU0jbFsoLTmjc(Ohmw49D26D9;-q}qHcPwBH z^Q=mlRlLmE#H>z+?}VdbQXaF~zdU9uM)~eRXv|e zZEt(Nwt=ox$Io{zcbAp9oImUW-GJAsP~C=19#w?Pn_W@QC*u!URp{H(T&?#PhhMp^ zFd$naU*|mWOOQN%l4v*Zg+=oq)VWA~PV0$VAj#|-?=tLIi61KLvQqWNA4?-YHGO$f zBoz3YUc`?!)v|D7HlNAOq&d|lL9E$$D7LGs$Y!?n8LZf7nCqsnIcmjLeQOf8A{UXK z)eSzxEl=0$>3&9K^wjO`GA7(S!e^bcVa{VTVKu5nSB$(g8sxP_xB}rIa3oY_NKH1X z=%w1VPo2GJ^^<$%Ruf;x+ z6};r3nol)RN2WFG!20n9+nolBnZy%P0d}je=-|k`$d_WM9LaRn&?cg#@r3@9nH&mO z-&_z47=F&H5k21mZdr)zot!}7;gD^!vN~%34M3nsK8R|C0{5)b{aG4O!lN!1CPDtl zFO7|N8cXbB;Dk5CwogpYXEhgHBjeKfe6hO6kJF9zA_pQf0aAy8;7t#v*TdEYdN#!z zSg#oNN(O5hoA4*7*Ji&Z#nArqvZ}t`m^{%=CeZeu7B#lNGW54SULQET`lDyNW|29c zc19nXGIs~ESK{duUTrba+x!t-u>KCwDbTiQb@Cq$S6h=r`V(foTlLfBp;ldw`mKY` zCvG+E(wV-l3uL=P!-B@Bk%VQ&j&ERJ6mGAk$Xom>gQ26ObB7D#(rzQkXo4!#Y&L^p zr1+pn)8WCQPNYkRpIUUe}V=jwJ62ys6=uF|+4@=*1;;VKhZ9aPh^UJtMG z(H{#U^{g@A(etXyid;pgGtl{zHh&B_K42=>Xib51JSDPpE~#?4fk8lxb`yrOj=w$g z#4hJ!u8(&okNO?jpzz4Fw+-9!T4L($%zqR+KALQUd4->75*0gS*Xrb9{a3#Grbgj2R%guJ%1o~*k zkX5-nGR$&wc2bn)cHLX$wz)Z0?)C_TzB-AV`m{yPuWF7ImHFRo)p>coNPNojVy@f{ z*Pjb0QhfNoFn)j$m!R)JA2kRbM2rnP>=& z!mFKy_M&nb91R5%n^)WsaaxZ7A~h%0)(bgpC(><>H95+C@WJSZ;DFeb6!sQ;Nx-AI zV|>lKhLgq{VI3fV#w~XZ}29^*xAifE|8@B#wbf?an>2C|^ zCwpUzv^<4Nd>H!H19A*%g=s+6vA@_pROp^#DE1u0QdutT=Bw5Cs0XvV=Pl6_*$RiR z4{)si9=iH{&|w8?8F>%u%py;AG=2~3%3A?ev7BO4E+DxKieVxUmQZ(*Ql6KzzBZ}% zi*E>=%l_yNGptWB@j8YNW8?nGYOf4+!lh;DZYEv?T@5Q_?%vEE{?TbcnIEPT00uhH z-ROK--&wF+Ot%Czc@_8(|C|v}`yMJ?w4sdz8V`F`RQc)s(IzAQm&5s>c@+8RuKFbA zMI2h)W12ox^MV~&kOaxD*0iMpT^KxV$7R<)_7{s>3iu@Sbbg&4oixChuH9Z;U)yV3 z%c0P2ZNFz2a^EG&=(Xru)!`8Z5q3}E(FLaMCV6&UhKuYToD96XqK)FT%CX?L6P(kC@tXW`?%MqK~6N)l&u7`u_%%sE!k8 zHnC4mq+n8&6Y>v+87RsdPy7zOI^|JqTP~c)9b#>1OcTqh^cx45L+g1ev~G%k^K4G1 zxsVuNZl`0`1Txa{{iS}5QB=+cSDqXnbSe*L5{4*J$=6K(y~$?UjMnQStyNJcV%`Yv zUYhB;+t2)*K4HGc2<*C6hpUa$&;0eqc3HX+#6{7uC8#v2Hp!YmfW`Izj+75r%Y%K^ zo*5j4T;r@26?`k(#4i*MI;`UbLi!iE-XN=qlnWIB=n{)kTRGh0u!G{43Hj{aQe_bh zocU4_%-FJe!NMmUgHP(s7bLVTO;d&chSH$d7p*^An?2ddYI0d94sd6@C#}Z})#9;~ zNGr59o6V*kBTHgB*PN>MW*{qD^?M|@9o)Pon%EkWbTVH`&v{2N|VkYgSSMqsRoUcSqhb=$Xi$>$mLVv@u-~E;oa?Eu3IytkcEN zyn4@Krbu%0o=tS&9Ocp0rRy8T>^{LjF<6ayas5ZkfVF#WYH6@>iA&_;a6)p?-Mg)q z-hU=6i1H)Q{q-YT)j^uO^F-O@o7?#css83myM3(mj$$v4s-KKWSt78=kviA|%l={i zAh=yLZvF=+EBk2AyrRr{0dt6&UQyfM(b#Ss57)5fLJ}8O&Bp#xjE;KO_9unbg-+*K zg=N7n-LmYB2d3dFv7!F&m6=S_O%zd`9wg&9x&^Gwzx$pik6sLkvqWy;AV3J9qXPSq z)O5oV|M#^Kx@W|W{)E+A4usZqp;5TB^&NF|qVak+GLL&5GublD%t=Jq0(s~{KmxX!k{ox9qbiO?lon&=c)duZ72ju}7R zpBJ5gZ7P7M8zs6_eK*}#HX;GOI#QEm*KZJ9h``D^eGaWfdsDgS8JgGmvaPy)WcAi_ zkx@**i9CO|duPJ@!J(dd|!#g7y#dGko2iuMdi@wDri851`N$I^{ z1mlk3HYcJitt}&IhW+&oc*K&wQlZYSF)Mtf{$9Nq(hW9%Q*e>3;qbxBqq|Ho;w64} z`96a1WGI9J4TZ>PxC;(@Z`Jj)SF5lDy1lhdnp2LyEJ#1YHiPsFMEpuNX$>o@qVu{ebA{oQX*gB}(+LZ2;FDX|tW6@TA~C%c;*)m_!JJa) zg$v`Kx;#?5GR#fj?$YkpY)?uXM$-;W`aQEsMz0A+7^^5oSsV3(LUCV|t=aZ@QYxcw z3Y&F_Q&;t}!00mtqR%^=HZy+w&ZPmZkH)TU<{;;QvC>3$m|g*UQ5LYL)!+V``Mi?5 zB|vZ}+Rp(d5WajUIe%qrxyZkpeggIjRun+q399eH*<=VIUud}%joUw7IX5{4F6}Za zc^{w@(2m<}_L*0b33Vs*(l%>*`jrI^H0gTArAa}4xEx`@W~Z=Co37@cyn2%N+aKwx zRw@tt7%`g;v22c7+`EQzf*5s zH{Xu{`4fAOXWsF4@2I3Ot+$Cx>*B}pVN}XObYbCv_D&qDx_JTEj}GoZ}|kDk;<7b8&Bh8{x^B< znk;XY3f25vU0IY^QxNJqr+AZn9N%t!scxGpJQLf9>M_~u?!(`3B%b7w8{rF{$l;+ub9; zs2?{Z7*W1!Xt)`j5Kc}8cX^)PNWfE7pouJWd(X1A)(NjwWLjOT8PdEj79qF8G3yB@ z*%&@Ce`|ci%Oe@pXuS6UJClevN?0d&qQG5oQE1XP3cWG!kcxEgN}70a&QfxTR&%mJ z1s&G^Nf$-=??FotR|H&hlpj@L^(!QCtgk(0b-0ykhpVNNup-M$Jd1mUV6uz_8xgg~ z?#?bkGOEXE%WRaE(2&cX{pJDNo>T-55{lra$lWtN_)$?=U^(*mtd_fXe)a>o8la8j z=&atk4>BG_sGuqbx-n^qM4YzHNZz;VB|%p<0TQ#0n4(O#2d`Ojr@kpey3-;s;5T}^ z((hby_+%~`>W)3EOI?F~3X;`!y~$?EWbcQt?H)dpU|+`X zu1BnG5e`RXY(1>!X*2Wp-23;Z4>N3hQ=l-d4dYEx9_{x77(ViSSJau*yn-a zzXw%8{VWqSWd&`P=imkCmWL8OKm}cD%*9RODQhh-23Winz7hWF6#e(%;wI0uxH>x+ z`+zx1G|(p~?EXKC;1$5y;K?lcQxrH}MYS zC8T*83P{`~mgBep6pmTFP2XADXMJbNV5==Bbe4P&2EkE#J9>1^Q`f!vee^ivtiir# zYzA+aZjM*J9z4MLh9@@2-v#pwB)AyOzcA4g3ox`2T25jR-(7eevONuVeQ^8Q( zYb0QWT2UXXG=^f$N?;kZ?xsaD`gC5K;h(f3XVNsbzMuiAb=t2RP2(U(mr^W@;@BuT z5#O80<$y_A*`m)hoU_2+JGVk&@sH$rFJ94;XTAew5C4y?^Neb$>)N%73W$Jo5D<|j zozOc92qFO#1f+!?dJVlQy(7&elpxZi_uflDdhfl3UPAAj_&o3Xjqi+e{$-5(NcLX) z-fOOVUUSYr#^qi+hT4*#=*noJbeWY(%=`EoO2s8ZDIMfw#}^B-=@_a(+t*gUP>haR z*__c!{pQ`t>vSO85k(t)E8F!YB87st3;cMcuK{MT7WJ(H?-E520VoBplHxH_U+_8P z3avzlQ(A2y-SB*wwFXSX=J+V5IE{0W#1Z)jaBejh^*~^CpASLy*Y)BPpSQgW?cPgP z)%_k+o&%;|rX?b4#vb(AP#79DePykLQ1NxeeIl8qOxtfhaL{;4ZQJ^F{_@zI4@Q9R zF>)J2;N+E$wM%EC*b|&Mg6gVtvKWagOu-&5Il6aw@+@e)fn`ptBHKF;Ty8rK(@@eL z-02$U_o~LEshl&sZxF{eLf?lPVKyw1!d=IW zLzbn6m4%9MkqZh_i!IvPL{{aAAZ)X$g<*@9W`5CSM111-=+aVTr(8T8w&Hb)6516W zQIsUvxR-u#L=%|Z_r{AhXvIwGet3!T=2SIy-|=+l`gE9_MmDHY5BHZu%Gl5*D6)B5}qiEgt9%Od4$Flf@vOel^GjFz0Re5cV zmyJuqxgcQ~L3+&JqV%$EX@2~NotndiD3jTMn$O-V-3I#cIb!Obv}zS`kO+ z5;bz*oYdoVrFE`+(&}7Ffl66=uL z0jj-at>7@Kak-8!iBm?_2BB$<0v(r8l+n%xhxU*NIk+L;)Q`|0lH!sw)5JRtRIeL3 zcNH86C?AlF z;5DDbV8()S`pIUkm>q%8+2EJY*XHO@5#&0dF_7+uK#$I~5h-mWbzr9VkV0u)%= zT3qH__eIyW}G_fO1!NWVI^(|aJ9D1lC51ju7|DQuXIOIw4Jc@no+9vL3$VERsbYd~PwqSxnWB zt7~V+^xMUViW+K^+APnQYr9E4XNPew&vTnz6E!SmY9*vWEG|h$BCka~6PQ`K+FjYK zV>S>56Xrn<;$mUBGAkc~{k{>#0qX(f=;rn*EN?|VIT$5xt2NuoZa%=?(KI%a&mcIg!}5FXf=M)(+9NU1#&Zd}0g?99fmhTgcZ7iMl69^=nK&c#>asP{FqO?p?y z?QusLrJZnai5eEA%}!>hyD_IkJD@Rwd|OUAxnEXIs)NeYs^Bz27iA>oEdst(gl`=^ z9fyEAMj=#{KHQ6x2gIj7Jr2iug?)Xx6k+u$ZKD?CaRnIthOzs1O!F8Ni`;mqj6dGm zn70((O>)XqzailFu1=74L9@{+F%T_zTT1uTeBmn$WssbA;XbA+G6maI*_<<*GT zj%QWRB!!q+1OykH+nD*+rAUCHxZK2QR@OKA_&ukFhadTxxq{uQ0dr~`byF)VmeHw6 zd?O9w2Nh=|R~}32t3hKANjxyIbh;>~`R|GEa?W%sp`A&C#c%ogBr_W{eEEu={ADTr z9;43xYxnIreNt=AQ|Mc)2M>aDdaug-KuS)bgkiocwX!))Bzo?(6ho$F6+@;)v578v zBlEuDu-&ktvI8Pepkdg*zvWd@q?O}XUK|n`w#C1xsVO)3V`I$ z(B&`Y!c$_W&l;9=j5O_-mdhe#^XJ|y|KK!vw96nR7@JN7Pv#cQ$B%W`o+YbxB>BKr zq2XS|1%<5W;!>!9mM-DE{iLaDA6@PT<2|XS$6k0==b-q+yDCq%{)uobBzZ20;o^9= zpuS>R4C4a`6cwIFJW{z@-Us)1xvJYDmlM+qXq5$B+$N`1Y>cCe67YRaxe_OrE%pP`GpRM0 zmA_Dn8Jg`xG?Xxm*vRwtf%)e(NbH3KI-GMkxgLY6HwHSKXCLHq?D8a8ew%v8$I%Hl z79S2l%P{jgj=IUIB=%;oG6Mxlkg^$OCW{eWjPm*Tv?Ynw{$15M5if+|(JP(23JW1! zD;${XCP?o({i0R9ytw!cp27kal!R$v8(2z&v;N?N8vs%iT=?M2f>4Jjm!}ni#;}w} zmoNH($Hyk+k=SjK;*_SV18yT`ls5d~fGi(i@u5j<0Uk-g4wap4n=qf1(j*_msbhGG z0#bJ`qR))ieaq>X<$}*PnL8+}jE4tzFrWpXCLz%A+=I`jlx_tnsmAHeQ+#0P2d7iB zUN=~(cxZfP23r=TQ)^;^)kuYBo~c@UJ)93OIn@p*Sm*mv%hfvSaG#ujkEi^=bjL(9 zD57#DCk?gCBpK)<(K%9g^uD%YU!^Wf!u-};EHX-|b||lbr?}92bFAXSpY4eX>;_Sn zbj3VnC+qodr%GbxMxYUSouQ2w7K^c;k0fTCjm`JJZ4gogEx|s)R45}8TFmoVB8W}F z;-@58izWs^J*0f-2z&=VqJbG}j@#1}bO|CXI1~THxbk_JBY)pe^9n7iz4bX-iBu8iy-W&Ori92$iXV2slbX zf4MkF_()9{`3qCj2CsO!eyoRJ!>OB?Jl5D+=XGTUsZ*a_&j+`A)daP3Qoo-oOQ_$l zS2h7#E=X7+XeGg_1RrSDuSj^Ud^N`Wgw%=3C=nUi`HU z43gjF zuftd-CAlHy&O7vOaj#F-%=fs!jHkm*&^WtSe!&ITxPUz5g5zm2 z7LOC!EH*{BqdOdT{8k%JiUB?I=R>{_QK!lYI4nns`3JE+5a`7tc+xiL^f)fk%z#Hd z%$pCun;4qY1Y#r80|%2xLI-! zvhMyxR4TGzMitms58!u{Uucd5Tq;LUTBUmn*$v+FzC3xJh95Lk^3Dzu>cwb8JO9#& z10CBeMBmqISFE?D2J&>+{31d;COJUxK3K@{hk*s2_~OZ2_wH8g zvniJeurzDL3n@af;L}T1D_IFCn_T_9_7H=_yvcznDqjljPf-tGrWGNZ8Y8gXjX-D( z=gK91He`jM+$|qh>4i`7rHbIyr=EICK#}cS?E}`i(x*|`?p{`D^~VglJ% zhPeskQ2o@z-V=D#koeZ8Z&Cl3;>+KWT;G=VrJyqutob))b11uR@l^JrA&|? zG74;m(v8tKAZzC(6o4TY>&SZ1Gj-=G@6Y!1fcU(anHtjSK=!3N5sFf{B9Ttbv)V|K zIw7^|HdmVILs}92B9_~g0URGR$!XI8!CSj}rPXyhqB=t|v`!;4gS`+Ew(qkfscou+r6 z*?wcIVz}AS@iDyj2r=LkJXH;MGX#&|>tAKVEKW&pJ7f+@Qocrqi!}Zq2MY0a_H>gG z8nbvsNWiTmf*-kr!@vLv&7*tC91jjk%FSXX_))^{mJCr`M+64&I>MuTnlGpwq%Jky zk1Mx>`B<|Hls_TvTxsAn3`g0F$&p?tG+ks}1akgFlRM#~s)xT-re?K<zZD0Woa=O2g*WH1Y>lPlL1!c!psLnC{}Xy>1cA)Qje3q0l-K%uH37b}i4; zFdakiJ8dgrwWY2dFFWh8JsmM{c`{1Av zfY5R0uyVfZm#7@1Y8E9oa(0U>p9a)9yZ4BL2GKd|exID{s06JQGIGo`dBs7z4(F`o zZl1po$pI~xUUU#OqDS4|QgTq7D|5WW0Ij0S}f^0h_AHHVWX3Z@I_N?Qb=nTGSmiXP@-Zy zedEM!OX(XUSz3R!lPfe9vaHMDlD| zu-Zb=dV7|gaG5E)S=G++hS0*t`XvZKp>N!=dN{7{kw_~@Px;)6``OJrHDmrItle(> zd;Pi&Z)+7qm^HZvyDUfC^+_ScN$7=bA;&?bF(R1ue&y*oB_^TnCJIuUL-QZC&rQ>6da8)0 z+@K+d(54gX`p7K4k=Y~>!Fdk*W5Y&&ma?5$nC))26FVVT`>JHLJM zrmz zLygB??w8-IwJ^N~Rk_Vbo#`(xvQ^?C7q3W3Q&`pyK1t3Ihb;I(0pt^aUsd-nC74ID zm+l2sP$2^lYLozT%Jj$4;Ol2t%ufZu!)kIsD)C2gOL4`N0--|;_>@v$;>RQ`#+KH8 z2^E~CLMSo!++LYYUEEazo47d&Z#` z(m;;XmUfg@@6HcPzj+gAAkZnP?Mw7##38K1TwKJgGFJLZ9%K`yI14$J%d#T z$PTsS&S`wlRJhwEcWajwks58g2rbHJsg9Dp$sJZ(XS}x*P-bCyM>;t<)+e@|v*YJ_GFCcw|9L3Fsv%B;3>OE&m& zcXRS5iG)rMxw|*jU;{;4u#3r?1r4YD;dtfU=Oby(kZD0XWMG9f1$~>3ZgvF#3efE%|DHGMA>W(o%M&cDZT`ocAviFZGY@n5I}if{gY% z5F33u%!F}B6#Bkmc0AJGa?tMwnm-i>KVCyNJmfHEx5Hz*cM~T!WE-Ue7;@gpCTW6c zRUvnqpg?(u9yMm0a8?zHfkh>L<9c`yZhWeg2#Kq!a&TPNP_~_Gi79H#!nE3ct$iba z)X!gE+!CPCEsL!mSYXQc3e|)gizUG;3ws@lO%dr5;WWu^)1Yg_P8SVC3OuD`oR~r=DTp}NzToZaO}%IA z3)c3qFq)Uv^hMyodOUkT%QGqy#0`A$^)L>$uz^qRJL1W8_cRONs}po*zIF|tF-@4| zYRC+AC9cs;3gZPdJz|=$3zI=QsLtk*cIk3v{*tw(=$R;5K%tyVK0aQLo@18UePGwn z_}o*6Fl&<9&|Kh=Vi~Kp6;B@8xWcZy4{g6Th73Qyj#JUPSTgfE=*X@wUFAewh({*n zu!D`Wcq|5Sb|Pqs`FT2JeV@p!FdKml0xEJO2r7MqMKF+rGa%~}Qu19-Qx9cqt2wqi z)^AER9;N7Trv0sK=4euw1KDbei#k;Vxavm1k03CyrjYEbJU91-h`NDr;R`P0xK)fG zPEh2C^iDFO1w8%4<{2Kzgc-nD$FJn*mH2v7Sm3(2^$o@1>%;BUCfRFHK+Lu^5HrS$ z0}&WnMj;4l6t3-U9vsEO3)XT2`aYt#Bb#*R>I7w2aP}LTicmnprzn&9jKUP|#XXgv z;+s#T_h%Vw8sPD8-jt6fxY-=7$KKs?O@oZs9&gVk(R+LHmHWENJ>BXZyq`ijnoWY` z;gY4Y&gEn`0axY}9d5J`n--r+iHfY{E%vr!CUAQaMs5^Nym{8V|I#G&#< zbod&jZXe5{1vsRrdBKQdqyU@5fRBK#4BhKgY!X!9O?K+?>*;g88KmE46ykv$Soo5+ zXDW3{xiRslkWBo7NMWJ)u0e~ql`(22k#C{@iTsVjQ`?De1kq9o*(}e83JtBEk9(?4 zn$h-Ym|}Lf>5Y+L7Yvf|zh(AGr~Hb^@`?M{D2Bw&`^hrIL_8`BZT^YDIqn8cg9V06 zJ1cB%CIZAmHL{P1db~Yi;wi5N!rWs;JZHvqmoVec$wp?Z=%D=b1EK(z6aU$y~<@DSSB`k|K{eIKmDGy-<#6TPrk`;j~j@p70BfP>4g$FPq$WY3XT@idU4A0vT>C1!Pati%sXj*l zMN^O60@+?}9oE7->ydczUE!GVKHlygTeVMIE@ZRh+x;No?Vg{jY_dBlhK1{j!b&ND zaet0<2LdNWlsnqyNV(07!Jc1^ww9?L+Ua+e_$$QgiODH+Id}IUMOG~yI<77xQGBTO zTBcc#qG4is{cUmotoXKJz|Cff808LZ8=1z!RujsPm@R>5e=WGNPS#srS-Rja>_4)1 z_0dkY!{w?RFfbJ&#H*|MGOh5<7MI|aF9E2?Xzi4jS$V+Ns1gUVjZ8c+TW71R<8GT; z5fMio9iTn%v%gN19JmoNWSc%$)BCZ+e}xYeCpTV|q=O8YIlyioL_vP6h}u!jha)`qz#>s zr1czbaCWUN-(Wu7Ri5a)8eHi@Jhd2uvU&#_0lb94>8Y(o*Ke$|o+6PzIHniROrdK*wjA1vmvXlB*Hp{a(d73S-lN)X`! z^+HZadVJKE5pfid+3PQ>FS|=BBp}u_a8{IyG4tW)?Ia?rEbahGF^_(YW>h>w~|{rG8y<;>Y+MJ&HCi;#Hr_}- zlk_OVO;fEmZYIz7^L!!kTsxO)dmd??iA=+CoN4|-b#V52Q%KdW^)&|q9D23gTj3jY z@5rL}1c3~DG=RQ^*p>ROC_f>Aw7cKN?byWJhjWXlhppO$_S86+VMg<0#zS@UrZqt` zV@aP8O&_MF*k^@36WGl@R6C)VS)vkR6F>LPr+mu4Sk=)GKO!IKcY`yH=o^;ovjflc zF?D);)pcB$VcNI|5cl%Z4O{;nxAFGz1IZrEmBw>58dQ`2ZoW`)%I)*h5&cdy!6}G) zY2!?k>%N`w{uT2N1bcDHsp$BKhJnzLDX;<2Ijz4~g%eD5gw{W%xy2}D=te8wI<;fk zN79As$l=iQc@>qSLn`{!-pKs3bzcg_yeb|cPg;_ZHJ|_-Ny=cx3=}k5h2cJ>5tgQ0 zep!1)Dbsl>V?LE3#JTN?ne}d1z1!YXZKZPQwB7O15GLb!V))V35Vl)8QsGWf%fGE$ zg=*LsDy7p)-B3AWx#B4{^<_S$irNf`fkn{z#oXQl;$s`TP;)?E&D%x;oCVupbRkSK5_@PVtK_U4js#+dfLYJ%1vYS=g03W^1vI z7Xq0vUL!k-_Qrq=ThqHcMm?7h3seJbuo;3dS4 zxMWA772zIykiEbF-pp=qDvb>|(~P}dThH)qN=)|FdHrOrFLd%_KXWI9l_8K_%fblJ zd@=f^KMQ5gE0VH&&iKT5rHde(+1-rNaNDKqY-E4xqU%GW+a~9{{yFo0uXi+s_`Jcl zDPmBue#=%(Ue`QHC;I$>?TZ>5P4>KYPS(=7SkA2vdGVqOQ#Rdp@t?F+<=(x^Wd7bY zw_2}ytp;LtsR6y+BrCa5rK&0l@h=R$X;)4ls}i{X(IuxKl61D)cAj`M>?ZRb3ubJ@ z;m6Nzu|Kg&@^#B1YmQRQeqfS>9$YAkD(IKh^H-xz+5pGn&p`yKt>4pvj<@beQ)*AslzO1#geni$=BeMPX%K zeOHoN@%i8%gf2gCR#MCl4e$`ZbyBfUwk$Z&tIZT+l{z}JR}B9jnWZZ>=SA)E_XH^zVb)0_+pv^YKp7{L28DRNwA270K-Lo3k!=OoQ%uZRK0Ba0MR+LBK#iqv2*5 zBd2G~;Q9jN0eoUgY+s##!!7*#+CK5gDK?|e1*?|M#P>2^zKd@&ub(WmmB5}UhvSJs zsRod9H1WGn4kr82%odPmpY(T`%$1(iY3|Xx=}~T8@pVQ1 z$$H6_68p>8zU*4cD8<^;wLzC;%yyx%&xWmrNobb%J+hG5DEIg8pXIs)9S-5$u^+1G z1!sxs`MV#g;&Ievh8n95#B)=Lf1a9KAeAJg$qT%2KxK3&#y7yyZe+*zT2jE z*42P%*Q}WqFGOTuz%7!DZ+^K)sPUDN;wvB}f>bA?L1}1lJpKhLzV%3E~z1MG# zt!I*=l#mWKwIex7m`ISi{hS_?sjz(#*P຾`snqV1FWGN2)n?B-pM^Tt5$5UZ ze(amnbv_+sRN3YRo_x+b(WP#E)Y>_mx*2ufO+*-z1s!-L1wnZv0y@=u=kj6u%sLxd zd<)3fK-+Qg-Q{jCPl_xZu@!5Bu4*5d&C&cvoZC`w>#|gaua_#twW|FnAIbH0vFfLy^~Y)euO(s03x9*|NzAHfT8Ls`6{kWxH|HQh;Vijd%gmf4*uK9sl- zT`H=7du_HKd%G)dVhd6nC*1zCa3X3`v4RJ|K1HS5tGuoYX3HK? z6-K~XOEyfRf-)WWU#FB*|=Nq=%Kqu32U?oi;)%yXm|w@>SXR5Q2fGpZktIE=geGJ8)``e(QsTcP^}uZ%oN zrvQP;?2?_4N6=hlm*8$4Rf{}y-L;&0)xr}8AJ+CUgsddns`EV21sl6;mIZ!O8S;qYHIS8A zKrmcAwP>v@LI3b{JN58-xXRt)LcaG@r@s}>ZeNw!2Q11I7rU|{AMl8tn#W+lcivuD z^CPvW>GQ(oDYYG;U3{7b{ju7eS`|-xiv2a=>i)KweX3sT_0QfT1D0IijuD>Z)i6w1 zOh=TEVednk%cmPf>Xv$P)mEur5_b^Cwph)u5u&qZ@%CCi2&}RYOc1e^n8;ygp=F zC6HrtRJ--4%XcgKF2tRc^;1T+Tx`s%9O7Lcg+F=A+;;HnPH)%t`UuU1S7v?ktA)1# z5z$i1gV|OJ-X~bG8ug0PR&>N?t=j>dK2hJZq0g?5ja>Q?TM8}8CfDk|-rVoONjxK_ z?*YABE}#g#Ic6H3@R3GM6K3n7Dz>X_wB z2|t9yG)QJz;`Vh4wdC7dgv(T5Ed;4ENO zu}M}SD}*)@Zfe&`!=h8q!C}u=)jH9I#f?qqHRlE21kn1j&|O=L!wk2PG&+Q+DPi7) z?!;`H{4eGfJtL=k;@hHeQ&GzvEMmMK#gbT;gs7Yr|BX2hoC3tgdx?flehkn$X;JYr z`+uN_ze)&e0{w*`?)wnv`T1cWh&y?x#4Szjj;^Nn%N#8`b3kE)vvY_$FW0RIy^3wz zb%hZ~Po${F+wp=(;&9$KZr0f@_HN9I=K7LWRo^ps)>V>uyMpk&&yrFrMdO=;*7Z>B zThSS?L>t0Pvv|l%azRwZI5?Z4?uKTnt~q8AnniLw{c2g$N49r@j_9NnEQbFD13VLmgdoE}*;d=#CEgxDUJQg|s%#i52xg zYmp*$hiG=YQtzILcIF)naAT;PDmtK4a8>kP0+E!r$ zaSg|Wx?S9+!m6{nev+(hoPWf7qKeD;?kjuL@uMerVO{SB=mE8`{U!obnULV&MIN>L z_GUt_qizuNL>gSv^tEZ9n8q5sWX`8g?LA@L%@1Vu;4w|6mATp;$)4bOj8CH!e5z+L zRFBV@SdoS4&v|bIRq9!=eZD^(|Ql7I9GAX~tIAOIrD@AXh5}N6GFMel%8$NNO@HZB= z<&8iU2HAN67&=vx3H2@};g*8ntAl2*=a=Yf!ueNrH##)Bcg#rYd6xAyAy(}R$(sF! zcbC*f&#tZ=exWta^(VY< z>55)%Yzu{6+cL50G%}q9)6&dVB(-{r2|uq6R!d7u4vkoJ0zS(oIfKyi`SrMK>2{0t zCdg>!2s6oNH9UYmf_DF|XMR+`_6bN*;-k>Z-oW5BM^w(=vfW{0tJjDuI5Ld~v0p_m zGK~;-T3CcTlQC6Q`(VQ5H_L}`UfyLw^c=L#eI1#=ky7RdP4$jL@~xK|?e&Q7Uy1H> z>moZ`g^I1(m}6JkUQ5R2;JQP(^@@lqWG{)~`)n9s=i^KAOc={ieq=Ix(-I4}{Phoi z(Ckp3QFNi#aZ{`JknuB9ni?94-CBByxM4p!EMcy!8zbw{+lK`RdR)6N-Q z+iLn1Y$a*m!G|{X;qwKeLk$Y-)8n48{e%KpY7KJ7*26!RB(Qm|bJ7x*PN;akgBq?z zDil>}o%h~h`oeAwm1K{fj4$RaeIcX`?E4-AizWt+Q>@bj)NSH;;dids@DLFiGt}E~ z!1oN=ti{-~rj%O-ET1%LFrVv8g_{bMSO=%BdVj%^Q;$hjUmm-EKJ#{`= z-G5$rjs0Cs$w4{vU#s@o^Am=>{`9VI@oHj_tX?yneWNInYv@hd$Lphw(uwJf(kn}+ zF$w`>{phGU?=a@{tnRP>In-H-d(~oQB)#jFy>9CE7wl~6$rFvH4=C&&1$R$e0QUfk z^s|%85wE7^@RV>=X-iv5(T?>+M@xiVGV@_%G=0)~ZL!5SDNm?WU*SZm;RK5!uI|-i zfPTR%n>is9-!o2;89_@uyXZ%I>$2uJ@@;1h9AJveNoLvBun+k46mr#@UZO0Pq34_vihm!`m=2q2Mx7P~H1PU|p0+9RgPOwC zVWmPuot(!Zy`M{G>BV+KeU*{GK%aX;=KX=Pc2_`ApMDF)ep6Rv#X^al&9j_3UJAEC`8DE(MirLD6;R^k0Phy~AocGrZu;w2Kd1|>vP0Qw zT&N2514xjjH2rn5F5QOGr^w>dF@gHK-XspkW3!+bfzz8{zz(|OsmG!NBKHV~md+=l zg;tEu@s01}lOo>cc?r*>(l_+x)N(f^3jmQc5yR2@E2`B+QL0d8{z)n z*+BryKRA0uSIyDw;x!!dRbv(-O;{phr0f4}KhQ++H*mg7b9r`)d4Vol{ZhPlUa&z- zN%{n-AIw#ERj^Tdmbj72eOnHLvZAzbKfhacEr0e;Jt!u&z!%6-P_k5wOT2B#sYSn0 zvJ~R^y{E+(llmk!9tySk>?{4dy!`VDsxK)%KHh$%1HVwesnB6}TA&cr-~naVEHuZo z)47n>t##Uz*R6L$Yu4B=wcg>a52R{dOF6Dxn<7&ew*uLl{;Y*J^(NpgQ;jZeA@QV^ zyVt^{mbVfVF`t+WJ6)?iE}l;m;^;K7S%d6Xv_l2|&4RB?zOzyC=*N~5b(>oN=fseoX7i0hxRvV1?^$V~?pjns|0Z`xeYq?A*#5cox5}6b!m$nF!`us| zw?!X%^Dtc_6h=pw_HOe3Xp+!Mr!FtNGpb)6_#Xf4I{SS@c)g;k*Qj1B$u9vP+nc%F zio=*>O6d=(8+xj7ZF{jlhzny7&(mUJ$lYB*N??!C=)q0CiI;qQF$V{j*E>l4PWQhH z9zFdw;h%eT_YgxtgmTdrB`z>;+*Bukls@gRw>MZig?cpwDWg@;`tl~LAY|%GHp>NW zVrtC5CAr7*Ol)i$TtmxK?~Piq_KB&9jv1C;`3HJqz5obra49&nJkJR=d~Ttz#aQc1g(0Fd+pWW8)G5a6j2mi-0=MT;)z(nx27+eaTZ2;N)Noe_ju<9 z&RBX6&aQB4uMN8LzgoD$B_!U+O!x?(51mX=5%)wkGF~_z?`i(ix-IQoC+7v3&fmHj z3~Dw1_VP{G9k6#9Z|k2~Kn*Gr*Dr_aa!hSSV_F@eT2a zBTmGWjAgvAnGwg^oVTPX=1}9}nV zyL|uAz11lBq2({dKY3Y|e?f!Q8=8uD4GW4kL@MZo&_Xj`?zFs}+rJjter8srVy;aS zbHz5c-id;Z)0n(eFf&SFsNm9owY3Wz+|trA?da@RI=F^HS#D<*vv9u&^Wj}_l!A-Y z=%17(_uQ=3M$~hZ_zD9)p=FWCI4HDZ{<}nbM<)>p7hBzdKVxRc_ZMZczw2pKRk=UX zBudKyMTacJCh3TPhH_lEfT5kRNu@8qhZiMNjDd{AFiK_n_A|z8lUN$x%3Y}z#oDE;}0wRZ>Ei!>E1zw)6QMfwrl1UH)>h_ zLQ9|HrYo4LZg(XM^2ZqW}UMHaz-+b#9`X2)xL_Dt&*=}MQgDxSM#V2L*7Ra zuYXWt;AKb(7=1%Ld=xrM`|hLpV&-coq3?gYEnAx<% zv1c&}&^Jyd^j$gF{AoOZtoJlY@}GMpTVDwhQIjY;&bHKD{JWt4(c{E#f_mpqd~b@B zcE2{dEOO^?zQ7y=h%1m4P1JhsxuIN1H%yi@UIG={L0gwHPh8L8b0M)C9Uzlp5^7LkF;Lfzg&KTk`muGWPlHf@brHDJ?vi%nWjp~D^VBO zTnTJrDLBuiDfW&q&2BEU7$L3+5T9SKxgMHO%s};hw5&pfT=#T+&X=&25#kCK7OZP) zYow&4#il*v-~mJ=6bfbD=rYbQ$HY$xpFZ}lA-mRoOdm9y40^tgW;W8=Pa7A{n0VNL zeO#<}&cD!b#=)JBN6!j~+^ObSj#I;lhya^8FfUD#!dS7k=qH$gK+h(M8rx7Kp;N0*@2Xnd8H#Aa2M;VKib_Um6pYVlWHIn*a&C2n z$8W1jSH_V-dm4-F0Cr;!^E4-(y>R*-aQx9HB!p2=%Vn%@@#CWH1Ah{nUQR}O3yLAM z1C2@_J!|IIfKlOPW9cpx5!sKj&+CZWM4mOKv<^O7{^ei(BT&S>6E{?uNmx{4hZ}nb zhe?ccTRx%WpB?r;TSimD)=OQA3M>~4(Q)bgN#`}@Cfw1~S|3BtMLdfd8f*K1v!XVM zcYH!qF*c4N+~Oj#esd(-O3xxZER27sFh4)SYNGH{laIGjZ=9MlyM)4>4 zy7pJQoO0{tx=mS8nPve*9xnrb&gJnGWd~p6(oK@b%XoFz6050w5v#u+dDBFHXiuCf zE*98X3tJR&;k_|sZ;Wa=yfObuyem-4EfE2P{I$C zBJXZ_Y|^+u@hE~*0lC`euKqDuqxH944ZmzlLPWONbVP27=gMboEqes!fi z!-kn&)DPJJnv^)y|;>!n1_KXkGT3?z|*-%%l zWZJ2Q^#3sqbXW6mqH4=3NWuk9_Ti)}L}0ofoPBF!%w8jbmLIW@{om^uyk+orJS0e#WGDV zlAHA>4{0yW)jBJZ?5=+1M0M>|jE!K@cC1`n9dmOjYdz3~T`WXGg0pM9jyn;W2>X3l z4?V}SOft1Z>-pITjxvy*lPUT9;G-ns7$-%-FQhvJJTlYgma(S#N_u6|mB(*`aM$A6 z&2C=e`}@U0;FGuo!%`3*O=TxB#T8q}Sw*Mq+pWnJXDM0Fxle!r9C#g3Qv3vg?)W}m5}jpC{;XUicO`TFV@G@u+*plZzjbh~CgC1n;?}JkR zw;X+g5?efMa?A?WiW*UOYU!5xMdNX+(B*_K)i1+;{qBgPKdXA~*2Ztd$p zxBM66cJGJ~#Oz#*$>)FGOTu(h?+@6r2y!Oat)HcLeTRmGbush*AF95>uj&8W|6?Gf z(_*|Cr{hExf{vCD~8E3T{gWwfC2ll-NJf zA0+o0h@+V@SoyVU&CwkXD#fSZwmnHqB>D0ycQq-yn= z|8*Gh5)+YhTNy?7`*ct#8R9Mz{1ZQM@N3P(N)cX^L%VYZRPE* z-UBsFW>ziZoA}x=HQMNZ*{n*&p=0q8}a?-ctz4k6+To>EX zotBLAAzci@?763FOeT%?sDI*XW?r_Y(TqIb=DTw8+LdPz@#I<#J|TC?jI&t0=y}RQ zLl531Rq~6sx*qt%gna7GdTv;v+VpufDLyLN9ui6`mX1E*&oXD6C8bu@(b$T2{?Abb~ z@mI%BMn+~dLm)Ckz^49R*Ed+XZ_Z)3IrQ6=f3J0hiI0#$9F+N)Mr3F#G^RkUpimPY z3rDM6>byZ&CTRJ*gj9NZ9X8m8cJNL6;0BCMI*D;^GgWP?N#xCO2W-3LtS;gDp`g-;^hR#vFv^^qp-mU^t*T@8Os5o9mRcjxz)DU2iju*;=i4{?Bl zP#veI9+Q)kjXJ)+LQMxx`}$T<*Q_KKq4M9s^0!@&Lsq+(1oz5j-exBpQo0rErKKnY zg-{2sVHZdx%CioGRwMu`e1=0Y->q#lSlFrV! zBpH_wgmdpBv_>M1D(?Nn|8EUyO00<<4F9`ls!ae0run*mWeVq>uYrE=__?IRwEubg~YY46+pK~ZyA{^bD^H;c~E zgM5JFf_M~nUJJ|Dzp>)Ii>bbD+#LUa(;nwg!*#~i-?VYI4DC0#aku{%KC7o6_WT9^ z?{R$!;#YV7@^Jnqa~>%tp9bI=BO!9^_jHKRs{5p^Q(uRI!Z8du%qas@zVB?74Qp*lEwVz z#JcdJVme^4R;nyg@RAYeRB2dGcOLuB^`RRQpd-JDYDxgrSd-r-h zWLiM|_8=jVh~1G*az>|v6?#wl?Huke*eb z-l+mSXsEU+xLlTu@=pATEkALu$Q^aVoDp(I(`q+?_ZTYu z48-OuE|1z8#Tj}Tq7Eb_tEAVOSFwg))qmLdstMFXPlZ*1g0uRk~R$Wbd z>3bEo>YjjE?=R%z2&Zy=6{K2qo>}UbvA_DdqZy8Vc(quNfL@m0yNE@bNVmj3nEX#+ zRZPLjb?-p7CA9GJi@fW~dy@*5*MrW?8t)T(b9c$vCp=@&EsX7x3a(m9ifp@D-Zd$Y z<2%N`#$j|xk0oYjTHoH($fIwg?OAhgXIz0f({94WvpBSgq;AIL-Txl*uE*@~R-W{< z+$XZ`oU+=^%#R?$1n7ih6ydLB?<91nGq%Q&Ap))Ji4iYdXL+@#^+&}`)oKQYA5&g2 zhK21-_H7jaD1DAVP*>hn8^>ej=}`xA7yfdtHJ>Y$ZiD_uoK6MVQSsek4rOM22@S7N)`WL!s^Nsj*nUn-R8rh9J{U@ClmG=iKM*FKh5Bu+HiW{%O z9HmX%PcxW^hj#rF_S(4|^5AB|VJ=t2tzECQbb8nM-6>@5xI=YeSvvdX(J7?s^e@g| z`0KTE?485b?C7%>JHN>`1JiF#Y00mC7v`Eszr^`Fw09BhbRo_ZM`ky;D$}*Eu}N^T ze35s$&KDf=6&PED)H7pVx3pn$Fn+QM3>{K|Gw_JzHr`UAlahoINo36f2;}N}!I`Ae zYCX7ktLI4>DN-tb2@-+s@}jM=m+1jMqz>uP1ISHLWA5;~e0R#$PgVcR6hy3~nz}EwS`&vsewNXKfib08- z8{2SrQ7Mv?&i~`?0*;$Ia8QYSIz3BS#W94%zJx_4kzI}uZ~-!2NLm;b!s8EP%%OyQ z)f-caC!bCmf_DhjPm%mv#(Jx}CJ1eIjQQQQ$J(6)LW%kYuX|5fR({FA&;Vfq(JDTQ z@$P4ykSj;lktx!}GRC~CyZET%YB~I?+uYW8IppoV9BolGYo#Z|_p51gi=W?~uSBX- z+ryJy0?12GqY736Te+>+;DW`oHPOcIYM@WIFwNxz}9dcP5N#a+<%u zg{sR%^MoRG#?Iyr(@iY)ryM1YMt-gb>3X>OD04Xsr76>GM2qm;Si zn2a{&i}F^9^*s`2-QL(8bImKOx^t4^V&>%KR@4h$$62zv13^i0>TY&T2_~!o0(YI! zVO4GW9aga(CqB|47!rkxggP&>Pmh@@;F=?jC-Lgyg)(MJ))n`?71tnD!l2f2CxnQ} zpM(Vy1{DvJ>UMe}d|g$1OM>ywIZAFeI!T5t>sJp89t~^ka`6Dyt6n=iH-Xo6&?sZ< zhNL0+7$yb|SjSJwx@@Sc&LiI;f4CwZlORV%Z;T^eL&MPctYX(pYEl|Bb*5X0D+^in z0ji?HEX!!l&ji>n#VoqJywuYW2mz;LC>!-N z;3X0!U+C^_o@vA`K? z8zuJU*&Vskvuv5^X=!ZLT!jiAiV6fJyyDPTpZ~}QRkPr+$V9+=UxV3JEQ>*~9mU@U zQ|mS(>X?miQTQy3GDVE29uM$i7vNAit|c;DEj>xrOQ)hWRn4uwsNrtJe90nStp99h zy1c6DCo2z6_e}r?N<8J5c$t;7xImuMs8FhkBPHAbkP)3d=~dMl!RlM^4c6;*atzf^ zXf<|I;+QTj=+Iv18v4RtXS~ZXl@dA9s8|#IL@~Sxb|<3%gx0wa;kv#%k}mR5XJWnR zWFC&-yqUBgR*Z*{Mw1w6l+zTJnC2=dSTX|-{K3p`YZADImoBN+L5DcJPc-f_HDxDSdc(Hn+ zicmNM7wFS&0l<8+4>}~Qq=F`oTZd>S17tL`geKbBEJ1QEtUU1SGTt~cKvF_uWN4fE z8Z%NOIY>(A<3#T)KCpm3BVZ+&HdrjM8+ zUg^F1&H#R!w>v0b_aSxT`S3o+EE~{i`v){qO9*ivlxy&ViN>EDV(YTX-uprt`Kb3v zD=T%m#&=&~whlHf-d65xa9uX*MOr>m2ApOVao7>oz#Mb?kX3&YEjXRLa^)G%eO{eRTkG2bAz#zLE zujX}8vT5ayNeYuMhx|1#td*Hm1O8Oi~X6+N=$D_q)9YZp6)`TS=Lksq*`Y~2x*+X%%uFmHgDjCx=&4o8#^&J31wZjQmeq; zbAt-hlJ9b|g*xJ^Mm@|m&Z9cWNNLhW5xrXcN#^q7bIQ(A`PO}?NXVb`*7(Z>UbLH+ zCN)CZd@e|(--M-0D53WUy<0R8C0GRWV=n;~!U&c4iVN$PhH!dr!l{uZJx&B+U2Iu3BSHL`tl7#j9uY)_pz6|JE|G>oYT8&!{ItQ8XfLyoY z0GIVlJ^F(}NA)D0kn`QJKp=fQg_T%tSQwKAT61XZ1xV1BP!2=iOqrtyQQ>97Mzu3Y zC6701sW6uk_{*W zU7x|T#50@0R1CW?wPv{ji$G(cOl%f(W_FRN8}^uvTc2aJcS2UW>SX@wV>E^{#`A-yR=lJb7vtj>{tCHXYB z-Z}-`s($|szLHmTZ@QJ2S&0ym^%sYWYQbXpKWsLo zsT8NS)Z_O8*V~GWm&u#Gv<gA(sz0)sXnSOPXmX>7$uTbDKH|9J)i`FmXaD8 z#RZ%LBo!c!^k*w&e1)azYvI!2PypR`W|^PA>W({;D3v=7qrHk*TtwwMMl__L3i2$g zKOPa-$R?&_0hcsa)?|^Suacyk-AGp8B0|JG!yRP496(S~3_mqT-MHnkTn_yXg!1(|lRO3|W(}^~Y8`Q_(!XJgE4*@Ll8wHw>wT0M zmQ&1vvR_7ur02;dwnlarTjgd~8{eo}1sxR}K0I}sgqW5OLJ!nle&1^Vz|qVj1)L-X z8Gy4T<~H@zhT$oL?WB>-57DokqgPQu8t-!p?*;T7c34( zCP60T#4D1PB`AkwgmMg7P=pUp$p(1>)fL&q>@1Lli{$<<;T+w>aea-OsB@OjKna4; zd>OrVm;GIlK@^XJ^4cB+A7@~#xM}HfAmnRVuSH4JXj5@Q1r>Byly6YtI4LkEdBmBt8I zz~b2jVGZWKVkjy@Fm0k@%pumKfZHJ3sJZT~q)ONa5cHBPqnD0dexB<%g8?1+bn+O& zNn0QPr>Ha820)UDUs%u~b8NVfqNw3g8(nem<-7 zTXkYz%Z>0P(pUY6HEMGy{-M!W5ZgVz3LTuBV3(Oh0Eq01W)a{H??b^0{@EuPGmgXA z;z#*5BT|y&osEiI-h?+~5+UtYif9MpRve>T_yxiRE;!6{0XVJ9qQ&)z75|tDt1_p( zF5Rwp{**mFT0&arG4OL*Fioc#i%zPxOV??~XZwfBN#=G>8IjYd(?{WQUi!igWI&vX zWHebe(JR#joqOlHnQy~NKJHb^-ySI3aCxJ0E*Wu30O&1I<>~qRUps>2f_Z4 zEdr@(=F5<7HU-#4Mu{q5twzZ!R7>9r>OT!kvr71KRRR3*)x8S9(_~xpSIc~ultHtN zr6{Mq`_1-`)RG8386zRC;x|=SgXkO-5u{X^af6rVxod+!XC}DDe=&A zpCs!%q8%GzfhJ!ZzE|gC+Cyvgo2ci9!T8f5jb$B{hbbAU@}GoS-VA4!*{)7P!ULEv z)Prhf0>so{TAs;a5I1j@rtc@qbu4$@YgT{y@@0~POm^0;nGYl?H_GVBRjIt7PebYjFB|hyni!HtK!? ztEdELQ))&<(i%8m&Ik_Rj4!watZ40moR(<`s5zO$PDSD@nc?2!xaJz6ND!+J~UAU5vt(cNOWnu8Pf9#21>Wu1C%Z1u3mf27GB>0*gMYvEcnh@tc9) z)Y_7ElQ$L768gIzmPX0v zA$Oc!B09c`90$zx`WnTxQ;KM&^~slzrPnW{yL1)SyLCNEVm)Mvo< z0HkjN6P7e7SWwN}^mO%rH^+0Pn6ry$G}SCXjVc3d?3+2pv>8mJO5gkUB@T@FyV(+Kn)cQAE8|2VPIxWY6e-~ zP@@t-w6C*Qu1i@V7{Pwbyu?)wq$_vrjcDi{RJcz4(`a5V(13iSK7en^%M88r!|eqD z?zIg9gs|Pia+qc8jGfm-YUxFc9a2Dhm`R0>7Gyi$J21@X$b^k(J~}Z8oXCAne2}t+ zRQrNueolkn6#>V@q>G^gUqWQfh2TSIv6M79on3BaiH_8+tgsG7%c5v+`*a^d%*b&= z#r=;{LuAK;QawQ>`g$Edd05J0RkYOEN~e=>zmfOX@YmYN%1H@`ZyUq8IL}B!07z@; zM^sk8>cUrUN2RJsq_sMCQ-wOUsg7T)n|iJ@e(0CvfyGpEO}1AH@b!kw#gySm)~H1* zJJw=-Bfz%Sm8wmXck1b^M+%#a@>(EC{O1Bl$9|2&;^cZ#Ih8!7BZH!oZrMN9Wmql+ zZv&kH2U=JAi9zmu8qX)puzk$7fsb!RkKDW`(UqHNVxf_hPnKxMMsoyX!2)+jhc10X z6SO?4y88GeugI#JY}3q5B;#P4iHt+a3(C$a*(sRiNGdfrwlX@j3 z8zM7)z9x_RT^Pz*`k(IUrx%Z50}okLerK+U);Yj zCxB62oidn{6gH*<+01Cdv3xC`?z7w;s*h1bkWy13x09v#2^2A#345Qe5X#u7W#>SR z?#WeT_Q{UE!W5(8TwezXU`MM)pE{&PiuZpYIlYbwEHLF|MpOJq9Z1NX zH}`YLmoR)eHg1kjJ_rh`4l8(;=l*-{$nZW7EuoKC`jKG`t?@=8We^LIMpRww$;yz7E}%rzyx!v(^}WKDACcd@ zT*)%11rU3G4DBud&YHZei}-R4#H9#7)KlTF;}Z$e9wpuX>QWtc5`1Q!63SwFpEicq zqS&hZmZOy|rzC2};DVY9rD$e@0+nOyVL8*_B$K;MFvBR>84<0xK7Mvx=sfClej%n zf*Ecm#g?fzFqn?B3+_yf|3vW9*FRdsn*yO=k_>qj^C}#-L>XovdrAl+V4Wg?mLtR$p<^D9 zh~q&(OqTmikoYt8unHr;NbYG2(>V+6s^xFF+geokzAAxDAGetyTRn$HOc~BwjqGG# z$hSfy^}=_)**)ltXG!h0^gt9CKqDpVDC9d}rTFbh!7&CCQY59`MwaMZn|@g4!@u5w zz)KWL&ZK8QmLgtw>PpW86ENdH99~tc#`(ifBCj+%meCk(Nk*1H*@S4sdG&H}I`0F? zhXk6t&~x*I5J+xWfK@b1R5G=-MVnFJJ~h=>x79;CxrgMawubt*quN~3Yn<6OC@D|T z3_X6+%tegQS`m)h>j|U#rp{Z+G^=TrI#bD6sydY-#^#~VM#Cfqq3XUb5%SwPG^}iU2`9KAtHUr-bcf$_SUR*RBRBYUBH_pMf=@1{AgACf|gtSGDmQ7%HT2ZKMKxNVnT>4QG(=+)uSuF-|cyr*yfyD^*^>e@b}v;dk+=(3NJ=P|wM zQ!A;B?|8l)+3zBsE#2iX8P?6#{+kxCImk1(Arrm-yeUgs#rd5a|LW@=)qCO_Oq7nj zBQ~ndCK0{uWfku7WZVvDa(2?iIa1~r3(8AowQ!@Wwt~Nn@Ofg?!9Luh&t5za!VB}^ z&?Xzrva(!;k+^64b*+X{C_1JU_=ju7G?^DcPtiU{g<6*==7OJT#;adziPb0D7~;wS z^Ulfg2l6h)0HdRB&a`?_Q?f{CzL9db=ptaez`o+o+*vd=``Glp@80`=p(jD&;=hdU z71r7{t|Q!XN$AQuyDbkYFUyEJ7O8zc$I&Xk{JHsVML_4|$KA!zjPzOKx*V-9OpdmC zU|sQ;uz}fNL~Ku_5pFi;f25}N7%Lo=tqgeQ2f@Jw1G%}0x@>z*LZW4MUy&+B9m-i& ze(eaA$>s*!`}-vx=2^%Cx~_Xj`2aGsOxzzR1{ix`--Q_h!dW#=3Yt_gXihS>*S@dh zNYOZ|UVbc9R0cUJMP(J&ZC zbwM|NfAQIg&ihuEgfV+%2A++5>-9{m=XT3kEEi2b-dQiYJDQppKX75$T`>*F;K=cR z@=hZx)EtSNXg}bi{o$Yd=(_OId0dA?hL`l!tKp2kD@W7r%;tD8$P+|=XhH1|q3X2L zjN*+?&22)>{N!8t*{@MDHC?Jwu6S&GH((m?^q4Y*gRqt_(qJ;gj}f3pZ*`i4VDe- zq}K&W-n}dg?9e;7zy8_XEf{`L56=zCG$&AvJ1GJjKd&LyyP9iSDqax!Ed*eQnsqXNk`ZC$&mZWI*RI$5*FlSEtu zG8Gs*OSS~33N5BT1(0*ysS~ehC%d05n7m7$R26Lj{iwY8M>WRNrhSHK_1kehY1k>L zo%rP17?6UE496B@ z(p`UwHoTXZe1l%?bv>l_1bCg+;Kq8WU_umTWV8eeo4(fjjIfA<-s)1;c~7j19rc>A zK#v{1^aDamP0B`fha^PTlY6deEwkn(?p!zZuDK7 zg-`t%qj`I6n;f0h;1+IgR~N}6nF!WUT!Vj-@<8kbGjHqm8N?5{#XoZGqwWZ!YWA(hkkBjxv+8dY6HJ&BfPgS}wn=784Pc_(l2aT<~QM6NXOvCifiEp8KY*De{-4J<`(Ni6HIG=;nHIg{Cht^eogT z)!&z$=(pygc+I!QZUsub8qVh;{3}T6HJ{FMJu(AwggnzV&^CpE#vQobuL1Kck4=Swm7c6>hkh>LovBuCU*E^ zi^L9+v^+w#kT3MSYR1E^+GX??#*V6NH43BU#r)D6PzVE#*5nu-SI1i%S_hzz4mB!{ z;%vg9OF{_n$)H8*Y9RL#Mo)f?+46nFo|Q~jH(fce_w$#hZP3FL4|_fsk9Y8Qk&%rC zG3L;<+Rimg7Q{=cN?h#nww<9du(D*Lj|~f1v|HfE#*hG&(p|v8faoM4g&X}F?VV>C zj7!Sl<=c>fT@qhRYuW7W!}OBwH#=?5oo)|rZ^cqr0p*Nwp7HyCLU5v@jA!tg3t$S< zY641|^NTrCL%iRfPW7FbI>ayRoMnk`mAcjVjeW@VUA{oRtDBzN(ch`+^yX`#dB#3s zeFhv|PjvPTwISGW{h`;PR9-dEubO7IkA$a7%!8IsXb9Y?Kbi_7VD5)8d0!vOsPDrm zG)4GvYN+JvASr8oM=Q1l(_~L98_K^>5$M-A`=H1eewE2&2$JFNQ^O?1p5eDIJB`xJ ztQYoG$p41I<2HE)wCc~CaLoU?Kc8|rQDpP5WVW|W`>v~IIQ!`g-t29w_y&!aUYQx{ zkDA>%ygVc2?TC)q{q6F+6YUm|*3Td{r*J*#yQRh!r0gSnfs6%rSD0X+Wt@v3VV?`o$nTl_l{2x*waDgdnqLM zAhXa(?Y^B>cUk|h56!k>e@R5^CP3)(?>f6UQ5ny*Y|I9X7kQPuh@Cx?j;DZC*mtWG z>ah!AX*J3o?j>FygC1zLjz=@OUy&I-p=;W_C0{BVlK2LF6SAhVKP+*3?7GEw?i)an z1%t6YvL4@Tb=RVJPTBO2E3F9i%NP8=Zd{fYx_r*B?kp+Lf8LZtzo#HHL>B}aQHiW1 z1jDgbL1w7bz(GxpgxhUq+qdg7d>P@(8Mx6P8qqGAi(Ht2H`(0jU*$N7nmm?Q+i+aV ztlWoPcZM1|(-}Hxx}|^eVg;Hr99R-!)e+SG7?RtS3*Yw*rG5FTQb98e`$JZYzTPvC z^K57hz3~Llw!lGP3u)*T$??L^g7b?_X?SbS7?a75IWGGN?YxExA^acK8c~1p1|+Wc z2!Ma0`l}87&5rx>fQujUm+e@Y=Ph{cw!e-gXH0(uZ^=F@&cN3YQRNRLp*`X+6%8h{ zPW+BAZj|j(_TukFxgWN^fY zf#mNKX#k?@Sd9RPpN&lOybv0)?r#v_%b%jJcPixDPo-EH|m zS?dPn-z7w)agqgBq@u5-Sz1jS=;lcG=9Q#d^m)EnH}=|t#K-nzg8TplG1iuTgX3Bm zF#pPYdXv3P&X!S80DHFD%ORG?PPI%zhWS4vaQ;zA$Co0H z?n<=BHVtlSwiApDf0YB;_+Ae62RuFX&vzr*oG42ubdO5g$`uu;S3VkCgSRap0~e@j zi3wR_F5z66V;nc6rVCK z`mt+~r{`q(K*B_YKk;2F<(=^9K*)5LTw*r60#&T;bVq0)Hca9;bR&kk(5S;x&;>F* zOfafrG*=_;e3#CiNE@b;_xQ^jQn`+s_us3+m))uDuH$9iR>5+sXGuPBgJ|qKUt#q> zKl0MC8vod*OCX?~Jza(5Q)R)OBs|Q>Y#_*qdmiRAJF`jfCtVop5nXrF3(4G6pZ@o> zNd+ZIkk#RM(nv-u`hMC$HS_uAi@N$RGme3$4A*kBO}38yqH3M z=ei#Rp1;cME98C~y7Qv1U%ysI$XIa$e!eBvWs2NELj6okSB5q(fQaPyf#=r&lDZz0 zUV;R!!jhU~75udQjkpf)D=K?d>ZK&vqiv^f*9sb02(fMA`pHD>WVlF^`pUS69B8Af zGsh}}2zY`KpH>xKtTBTxH)3%i{b|5Y_!8+jtN#qLRE1yr(5R3nn@=h8H+G+DB8Gmb zAws`UoDHPYsG#dT{sGYeY@cp(IulS?<+Y{7 zsvskula6ZRP0f4SCY~2fW##2pxC3TJVt6!TH+cF1W8w~AW!~`=DoEVoKUt|XpL2X{ z73dajuUU{FIZ4t6vJ2JixOW1n2=@XhcJMRA7U4wJ-`ltWiue9fIJE129d&2}54-6n zBQ5(M6`Vf?-}P<%4x&yCqQ>F?Yqu9Po9#`TG6*vea8uaK453=}WmQ(0K@Jmtx>~nm zSrPCeD40HELPz(X>&NzktEq*hj{IFQnv7EpQYGwE&7U8EbEzp$kA8$jmDf$d0PDTq z-XUiOed|#LLKm!@1{@)Ah4S7-^jmYW8p16L`J^w3z+yDHqZYO8#;4S1^%5vC6{Tp& z1Oo+F*)MI7)h*(@kp7;&o*Jdrwkxk3Og8P^N?9{t(?h!u_u2o|ZqfJ~8yvs+Aj@Yo z1tVS4Dr4k=%{F)&zmgJMr@KQkalDp9U!;xE=VTo{qs|U8kW*X6o-LY2q{|7*x&^UXSI)~CQMqdtVkNWtR$&g zlt#P;p+ht0${Y!f1!-l6qq-8l-{Ls4i#9NYIkgOy^#oy=O-hd?096S}i`h%42Ub!jHi@vW){P-Y&Y<+cP$|Je#?0zKeM>6_V30W!{gD?C-vgMO5 zqXCt4*tf^-y$!8p4yGLdi;vRoAG3qSc4@`UUtIklajk7z_+dMZhBE}ZPFs^Aawu7s z^58vbG7K^es!Bu&7OM>Ouz$8mSN_n$O+Fb{HCR+*_VoA@X>Gk%!el9gJH*W8Zs9PuqB3mu8CPU zv+?mz#ilezeQN$buo_hW4p`ZImx$KzT&br+p&mcw*H59`vQIMiVgye2#2<|K{<%Ad zA$Dq^Osj5Idj2r@NK7aXiDG>A-f_NM?=vV-&TG(A^Ao9QyzFu$$)7)i+D?K|Q72_l z^64BW2`Oh>CYP|eb{I`lSKpEEvsei)x?WLT*dj@#$%q~Xby!_TBHu(S5@;` zOtiYYEJZ@7x!(M26=jlk1-e6@ZVB~u!mE$;h)`!yi;tAfs`#Xc7F*oOjJk*1Rmsvmbd-V!s= zq88`0H=gj?ZuumRpPo$@_I)m&Ny)~`k|78M5sv+|t*3DgbHod9*Cxz5|NnOv8``*)ttHAnGhh-bQBhYUPUI?tnn=xdEh6 zvS?@UVRSA&VU8;TH8j!;U-95KPdS|5)%tC6%tcDsPqXE!8dzIJp} ztVk+EL%<2Wnwq6|R zk)>tEZ;xY|L6CQGFM9GDHCyC3$&;*Jf=yjr$v4)svoAJi@YaCJH&nR?41LL-_UX^- zSiRd|knxbJ@j@8$fS6(n4M&M55;k%WB1scg!iy#Io0>9N?S`sFlVOoX%f4o5>P zm_!a-|E*>j&P&7NO}{;%Pl-Vf@p119ji~d@$#!%X@jn{R5g}0B7lysUJ{$OQzHyda zPJZtqbZrtKpCIY=NH4s#QkBXTci#nhlT$Y0L_ojR8R~AuST{AxY7Gs&vpD_RiE(Lg zdh){TyKuLCsdUw8z4*>4E6VO2oH#l=31;Fx{-v>}#0tQS7iHt6?rx2r;<(NO<0ket z(S`J1L`*)$rd=SxbR|)=vSnou)P}>vPA|oKz*{=xKKKc*b9-8|?(4VDV6ad3v-uT^ zZhY1;0XW;l!pQ@CKsxxcfhJpr1->Fn1;eW|A%fY?TD!!9in*ALVIm&6K_Owh*p(0* z9xkw1sJJYdaF$|be&BE~x1etg)%(koRNIPq2`$_UK4R{5rA_(a~7MhgCxcx9&La7JeJhw*PL8h?*(-w8Y7 zl;?R%vL*Ad0NrPer$%E!*0dvh;ySs!TdkS_C0{b*sxR!-*pP@h z|HPq}_qxR>_d?JLgErp&*3^?|(xL0u)^M}uZn<=yy3!n_9yQJG&P6d$uxCEe6Wvo( zX4}^0$_drcT@Q*mst5askQA&E7HR~6zCJg=BK#n#&%>FI^8vA>MN44z@Jo#M#=me& zVQ}+t_cwHpttxFv?-q5@5|G;`=Cs+8W9$|0vvF{inr>=%6U7B8mdECh!IIG((GpDi zHQo^KMF!eH_;A4e#sY1vdx9I@wj#-F%aAj+97KE_8}QT+sO4we$-B5-U-hE`qtje+heb*nN)Z$dpX1!@cl2a4Z{#a#lhW)pmnPJzz^ z2F{5W!>{9ChL-+60IEP$zu#Ji466&dWOw&}^Cm7I*__Qj@A?^d;mY&T{@(4d=DCrV zu^aENegrRUQju<*KA6{;jxS)cMom^DNe%~rOY4fo3)`w4_hZO4pF;Oid&nm0QO(U7 ziBpd1QjF}m6kg_Dq(6T8V4>q78!Cu@aqsezN2w&*e!}u8CU)zLx12wX-B@2Pk~$k$ zis^IbwL>v@!9FowV;Q(EKft6O7ebv?#jk*=P%54FJDT(_w3_k~Y|P)NTs}2JTF$&Q z5((h0wT(?RBD<3x=r5fq2@)ho`0Z#p?(#>0C%@oqJRT>HGxFGearQoQgvAfvkG5^w z|2OZZg?*F%xis?^&dlR(wx{AD9312E=yFVH2suB)?IZhP{A(s;&^?(`xc7_}6<&qN zh+j90xWpY_BPAmp9$h;2-$cK!d__!Xwf|M_1v4Lu?z|dL*Zek5+a{S%~^Ghucgz%lnaY3+Qn;-Y&0OxvIZ9r5xegP8#&{d$nYOTDAkOtEDek= zUjW&-d5Cv=5&Py{XxH`}+;Z15i2mwzy5VGKtUhQ>JiC|$IYB2hX)&T}L~gDhI-?3c z<(s&wNcdFrcCd2&RLdg2f!up-xi~iqVthfV1F1Z{BqRdD&ZNkzqV=(Ed z7vQ(J&KS(&?kz(6iA+^7m1Ef#EAk*;I0j>`--*M#vZA^Q)j@H z?T282o|v3qR+Z5GI1RE+LouQE2z2N%77IV!fk;V-Apf-`bdvHq)RN!DBNLUz--S-+ zJd5pK+Io!0o&G67!aEO?q06Y@xcITRkV;Ms`%q0~5yZ}s5y75>p|sD)OYgwzNkkBd z@s)s_9onh9$mYbXmZFb+^4Wohp)&Xl|AGZT?hdu zw$2%aR{dw9d$&HAJ8Ldh?+wAr4}v_T*t@!-?fEa@_Pb`Ht*jL$j+%p4lGvpZxgh_x zG?gXd;c*w>Lth0vYySViyh_C*7|`uHL~(zTKXW-vFps+fWxMrIX_T;NKfz1mI^vRd z6JgLKAvJb0ZkgK~{V#n68F~vWs!wratM<6%OB*z~X4p&z;dktW*KdMu&G{sg=V6yF z0R5|XqQ~%aamQ`J8eI5%-8_u$elFhF9tGbK3%7#u|cmD*|YCmEyK90 z)?lwZ0AI=%SbDh(L+_Db|Ef!vFp_$R>XzLUueGN|o(- z^y$_M(|ZlV;6cOj*jS&41!}b5NooM@;&nT{8j$&V3J&<2Ax5Lu~>1_)e~J z9HsLbZtIO!SG|qPuOB43s*gM8E^OLO3dH(ecMPf@?nc+~&q9$;Zr6!iyf=RsX8dbC zGU+GJ$H{F3`2%QbY7p1XLBD_ca;9J&KPe9pf(SX%99>X zS7DFCP7d&Acy!P?xH&2fevJvKZw^8KId36ZrH9w;K@OeMk!cp>!WhycsMkaO_$bK6 zFG4EWEtgRPy?WV}{nJ#*Pcx5P`T9pKRI*y(S&YXUoug;4D0~ZXaTF zer#RV2OX!ZhBatMK=nE14R4G4ZoUr+jU9V;e}gNg48|>QA4I0djQyWIgFeHCVvmya zUmb^HmmC(S_l&_j5tJtRrH72Fnp`1+$&YkFo4d?tXsT%LvX@f@Pg4j5YiD5I11_ja z<8j^SHh4Ojk2^tSRKfekFtqF18^e2!!q5S?VDZ`{82H%I<{6=dzEtLkpq4%UD$E(O z47=-&i|eS*cp6iCv_-EGGW3+q#w|~Oje{kuf}{W^Yq4&o47~=9gsjgfj5==;w(QOp z`ddnu&RKj-jfbfivK3U8f9u2O)%y~WnaA0!IiJqP_`aXvhvT_)FLG?SV+;l_qWff{ z2P5{)>kV1=f#}w%9R|&rjTfSA96v#2V-}n%#-QV^OL5=)s~{t?*L~Jlyty?Sjcf$V z#q<_v;$T1hu2VmTVWY3bk9?zb5xSNV$mb7)Y{GY(vx}-~9c&wK!1@1*MWDijJBEzK z!}23yR?`NaEQBjSfd2C{AqblAyO#zy>}L8TyJRy8qR#e-yV&wAY50j0!QEGiOw5zq%UThfhPiRtvf2 z0KA2T)Sg@5P|4x4@5Ht%=U~Y4^~h2fkf`_&-)&rr?bdB@$Hw8Qp)!nJyahU!4QU6~ zVp{LExbVKEMDVq6>$l*(b~4QU-il&PG(H*G8bdxICxy4SM3DC8g;&sNTpQgA(R^Ho|9g@scm;@vE=D=&=0s9QF|%YsLZex3ae zbQ{DM2(J-QMp$9aU-=3sbp`X1>L{jj_|6WuO(13cofm|6Wqq0li7)YTu= zV#9bDM!%LJWV8Ues0=U1g`{J5#0P}FaQn&`e8th{LN@$ig!lw>!Q~uS=F>>aX%~KW z%}c|71@kzw{+G^_1PKx({C2b)clo1ms(UR@guz++Y`ZwX$9!?+vd7S_T|3cJfVm{>Olvp9NDkG$*vw8|u825nTn21iU`XbpR?d{7^p`(iq@K`Zh-K^V;6 zL+wn0+hj*h>N~i6`Y2rdiUPXVreoZUS@=382O4cWluutxysrn|UGpuxIeFOo{c23@ z-WBg9<{<3ai+AtrgDF?7z_$tuyodH-$<;$JY2L@s27HKrwJT(F{VTtSAX}S&gXSGD zynP+o&VCKbR6T459>5^7&+{LB9nn5NV!wG@{2nv^8T=p*!cg95$#SkNp^9x(~yOZF2a` z@reHDGW0n2O)-&V!0m@7V4-!Z@y+_}C@IXr?ro1@TCYxc>>D{svU3o<;(TbT1>zRd{Sa^Q#LwbY=P3#T0 zq3=xG@V!P1pzKwAiEqyvhru7|5NF&hIfEkENvmie0c1 zQBCxf!sI0)e5PO?Ip)XMDJN!B$Bc^k7IC^Jg1INm&KEb`yQb>r{D zH$h@-hj-w%?&o7kl8yKkxi8fX@ahgCT^@&!#fV+0uVY5r5xD!UFnm-xt5ykzADBJ* zw&0R39dO%5H91r478K&hF*&}ABBc!%!5N*57bnntUj6|Jh(wkX{Y%=r4GF1A91F?u z(OY+7oNOqb*3qFy#ncgW2HKHM;tg%bZRFgn+!01qor854wV?=B-Zi{=tf=lJ3sV+A zPnS|rMdY%v0s3v*ph-zab$(D}Jq~U)0Z%%qY`WH6cbgS*QvN`y9#0R9t6k%G6ZwTfk=dX z+x_S#>xf;t5JF*6{`YUk9T&|Z$GkPV^&N^UZn+;@_r{5?W`4T`9+D4-#f)P2I=sr` z?sRR3UOnlv)i|M}=PcL(1v&c8EstQtup99qHRxXZUQ}r0Fx%XSI6UxK-@-+MX5ra` z(Ma$_W6LBNCf%eWJu64hw+Z&t=P;w=JgnRMJ@&=CfPoz*W7)~0F zhCsLwca01kx?YVNHwTefa}s)T5PSEz3u|dCakN50~RcT2`TE7H6rY(ZemV_5Z_ravM_94Zb43Ei-BP3H6l1ppCy*Q`yomg+s zqd>V9w{#haTMi~6pl~4ht)Un&a|Kl95G*z;0-AK_{2KUma%jUEg!D$3o*+4!^&IvD z4VJmOKu_C zkk2-aM71)*gRj!}A~V~F)a{R8M)%gZ>ZNR^$6v)6AyZ`l|u&JZS*%BaMV z(mJw^en7h$xA&TffBld}wv-gBu^MGHSy*@LSjf7_FhbUo>SPh(^K*nn#PQ?s?|dDp zDlc;VUhMhu2HI~ZUjN2U8(nyN{&?ab9q`HzW<>IQ`0=yr(P{K!*vEs=@?+pK=wBT@ zg>tghHx8EJ>Sw4fD@&<9R^uXSn`JXTMTlcKS?^+AzxmkC!M+9!uB7XEB%Pmm^W$yq zs>ctzNo3?5KXGb|wcop(KA30JC=m&#WApvP&|%h_WMAIIiqT{7{8l;Q*586Q*L?gbWwFxrgL7TTC!xrZQ~W3}hy)LAQ~YAu2T%y6`7>pz|y&*+lusOuR!N> zUP8P>N%q1nxK<8*=SeA&-yA`%xtK zAj6RauU-S!v25gKXt4LgiRd@sUF>u3gk|f+Xf2zL4eB6lUYnS#BYkyebiL|xsFXS^ zIj=QF-L?SgAN5FfC&3f3!mUst=Kk&&J^v-BZN$TzDF_re@b;*&82Qv^@E^JdgW6t) zPfQ+U1+$@2Y`}LH^uUnYKZi2pN14Y3kNP0#vzv753}fcC=|uWbPZor9ivwj${%VS_ z|GkHB>&gSPHi&{%Ga;MzHPYZj6OSWVpupD$705W^gDK+>UYtT)_~PZTm+`SAat$R^ zt7W84cDy{YJ7#=AM5|s*??Q@rjH|j?ut!j!e&QunJOSrV-zzEvvm@TZMvb!=uUp=*wIrl^VujQYcg@fl_d=!VcoV_S<=#aYSA#@*hEfO+zA$j$` z&}ZD!IA~0R+?#=LxElKB#-rV&6*zF%jpA?b!t_q_@J(_GlJinvjr|T64w{13zDvUn z;_yYbD11J>2gbh>g}9I!&k|q1@{wKGe^_B3K_` zW;=3(zuthnKo0b-I20aIBQYxw7PDCmq2Nc^b?CJLK7VgyacO?0Ow{be3V@ z6Dd&WcnrM*2o)5HzR>1i1Wu}?NNNemIAZu%A)rvXROBG8!kLI2r&be;S%$g;vJtrK^Ao5$Qb}&oA>7(?IF`tZMb{%v0yxTjikM}Im|YkJ>t>@p z-DgSzkIO>kkh4$~UW27$&&T++>gL?GGCFHLkAXt_oQMeLfnU{@W;{y{&J^q@;~*d{ zf z6h6}J?3yyfEE|boQ(qFZ5;l815pr6i}2?ESgLKWV*1#{NIS-N@&6Czojkl3*LUxa1sVTd#vi_%CYZ;QQE;{# z&*q$|j>6;Q$ey#t0J!azNh#CQt9I-Fnk3r*mVlW39JC76@ ztT*p;L9SKfi`g9HR-xLS0;P(a82iV#uIEhLxWR~+dz4 zg!ho=s)0F8jj~cF(#TO)>*R1-?XYXeUh9_c?^LnPrQ zY>9am=MT6KU)jGw?x7!XW0&*rb=->>*#1JSjg5j%xe>43Iv3}SBKhsy6FoZ(5#(cC zx(!bA$GCIY1T5K*0KY4Ul=nuV?X=aiacppKSPE|FZ>9#)entFkLdTtpwBt)z^~Rq>xqXm zdId(by$v5b(~$AeEn;#f*|;f~I;jgfcItv5y@q1M%mqj`#3L&w2@aheK2sKK9N2WH zAjFdaoFSM;5=;w8E7>T1syI;w!y^MAdnirJuE~Lcni>uE-+nRX{Gbr_1w|%YH@Y1b zr&KiCm#Rk8h$;y+2k)9HQL=G1WRt!ksV7@T)y5fUHTk=7_r!B?**h+TxGQ@(+oF18 zaka9-G&Z56oOICjATEiCA8A*#MW3a1(vo^q)MnCkm!mlM zAg&wQA5Xp!Mjq*OJ}b}RAa*|11>G)r3%Xj;!Q)}X-+lomU$X&jk|DM=HB>T}UBr#R zaTj*oIubKh`$?gTk@k3Z44JqV=7yhUNv}-7T|`Q+jHBah3V5S!J`W&qxJ34h#d1E@wTzJ{nG-J(=$4DECp8*uX&!#MM)*kTrH{tCzvdY z*=(ERo-Mq}`VW@V2lIHc7?;lg<+|%IuK#V=n)VuI480B8G-g=R)?nt)so1moWen~< z7>`8-kQ1{Ds~)@zBPRDj=bn==g=JE9F1Fa*u(>wl(H=8!^Oh~p8ooqe?F{stwhl?Y zLn5QiM*5lO(!#8@L;1;U^y+mtqLMQZuO)t$v>yke_rj3V1e59qY(2jd`mQ<%74fND zB&5NJIXP+c2>2HTW@LfzBTfb87PLvN<&uM z%UE>#O!RHv9{=<7JnSez(KW9x}|~$xnI@#iXwNG3L!!q<%7w_FW2# zb&D9%C6n5jy_d@{>*3wlr*DK9kdA&P~M@5}a=+|+UF@AHadk(Xw zUxD4(Y;&qm`tn7PU7Q3D)jG%3Ihe-!kYDB(a*<=WiMZ%}*w5=}2eJ;L$3tDhy%;CE z0$6LdHe%IcgJU zqxZxYVc~h$MCsvToNTHSy=0hUaM@gDk;9Ed=lghKNLx&MNspcKtx)Yvg*GlqOsMG0 zHi$_q4qLY3nMoZW>vK60b;qH!#v_}D&Ut<`TFw0wX>K)CMkO3a;t)M_7Fs>`Htf1r zFrT}xju=kdpf`H;>yN$zCJ;xMi651lp?hf#x?b=il0p{vReG3w8F0Tg9&IPDMvPmF z;E&H?VE3EwjY)~HDis0WHq7tX155Vlpz%8qu^zzYOS@y>%2*sri^1JIiD$3j7&&|d zM#{RO$Jl=8-F+xt`0Q&~_uqhigCD?mas%?6g?G+$eRqkh*0F#?8G_OgJYS)kkCn_IlziSc#`)ygv;+$E-cO!8|_?EU4Dup^?3C z{+i9uI;{wsGqC>YbJ45!<=EzRL9c!f@6DToaTh;mJsYy`l?8uII<=T zysVmB9G)Spu@ObILJ+T-Fm~TJ0-f)n@6}Qdf;fiT>r3N=oXoCxvs))W<5+x%CsFpl1 zJ};586LcJBTQpV^lMJuH@IDvekdIuNW3--_B8MILXuWWg@G3;G&mN0M zX1B&AZ#hs%T#p?N4gi*wdhtN7fw(t5OYB?5EKvO>M)sJC?|6_Sj!RS@B}b30gSJ=D znGVj9Vd~S#^z8_$zT+;WU!kasjyqY4$`kRpe?VVcA0kZ~{Gx>$y;7d{7#=@^2(ShzhJF(%hz^IBozMXw^-Yek`H z9|Cp{lGUlOr7BTgk%W(LoI`r@t{6v7IKJi zD&5KS-GlhOPh)!b$%xV=Lbv4s43JI2^Kn)<4CyGgeT(_jP+qcGFS;ylnco+ku6_p@ z>U89l6+nOBMGWpa5T712ki%$&J3SgEx;}^cQ`|w$SKn(k!4tg>Q-_{|4?o!pS7tUG zPIBtBq-Q=8Qrxk4=G<<${=*&68a)V7Uo3 zVE^pp_XhJ^n%8iFtPdV|;xhD~_bPU(Vv%c8VCl#nxc`Z((Qe=sh)$0~^4k}p%Y^0l zaL0O>a*iTz^V1mCXEHXZvPgGd!;J&S;pvT9agNlFr=Zi6H=wqW(YK@{mt^0WtrfFt znS=2ND9zBW91Ynyt8maCM5a0pUK4Heeujs8_QwsI?eOcPv0+|EjD8^scAs5zWla2# z2+4$v@CO4>Ig~JNyag9dxD{`!w;;Il6mn2AYy}26Aif|2kvkdG|Fh? zMRbBlnGJ3@tv1+9F=x)qBYEa5@j9M4nZ)*FLm29nQ!rqG2GwM*j>99ycU;orJZfiq zV@PXiZ-)};YSR{NWCL-G=|LrFL3Q(lNgT8Ad^jDGCqIWHM{T#UsM;#BVxDg?LN*a= zS#ha=3c7lF1kG7Z6;)VwaclH^LW^qJT=r#evP++n)yhN_w*@sCtnM$vMX~g~GE>+t zF<>8UtFEI1PS&G<&ri2ejch!7#b9)LK0y1X z5xK`|n{7JDb^Qr?7C#H<{r=_j!91SKOGjkhvG;jg*0v|^T6_b#O?w8(W;5y04_G;M z0RFX%Y}C-35S2i(|MvOlFn9^xiTw~|YCS>;uVO&I3-Ovp0h{h?JkVnd?u}6*%V&h< znThB+>SHJ)$wKzbB;z?QEy4%(b7eT^ zbrtmHL-=I248xw-jnpJ1N-T*md_0@#sYQj)9~h4A zH@*jxh3uBihq$zZ$n&Qn@rx@ky!`~cvde>wj|{}Q*S&zPfe?ZUH!3_Txa=87H<4Z3 zvI3n(+={gda&$C_@MNkGbwyY7zI_8yJpq)PW8f!8BUNW0-8#K9)J@ipq=&dxeU%6v zv#@3FUJO~sPUz70d~|6mL)*4PA!|JdV|pwm9!GrbFx6V4Ti6z!n8j86G-kJY5T6Ds zQC&?Nt9ej{Dp+nAkC_i7i@;tf7hFz?LP}C|@(7)a_Tfgei4{DLWU3qmB>pAlcQLZ# z?f8~Ow~=2W(L(!GADD}d!{3BXym;ktA&;Pe&Mz&eU!-831PK!UJhU8l`Qvb=U|uU> z9~h1G#7pRtXR_rPZBKDXUSCpNNL;d7*m;hBFz;l9^k(vJzQSX~n=W}(4ofz11A`YH zqZ(Sf4LT2T0sUSadTK5@_c$L{PVS0ni@p>7pwF-u@hdu_`_$L5U9%tgIYFpRTd=g} zXk7bQ3^W<*Ft_yxyuafhj)%O+%-MqsXFQCS^|)!!Ff7}pfF;uluRaPNPnBWPDlLqLD6AMR z!)@>V2(Q)-Z$J+_5C3NILmAA3GwxpWAAC19rfK0;rNHgokGH1{z=W?&C{EjlxV5t} zX7(Cr0(KD#Fsb%pepeZ8eSbXy^&7`YaD}Q$N9N?K@-cN8b`*jE3gDm(ah%4BWc(Gb9)+aHVX;s}GIG z*j9tE>YEJMa-tFU*`0W4_47E8riU#o+eHZd9cG{qT%c^v1dEN7zM?1(n{->S~*iY|OxRvqL0T9JZ^l?DAfaP27om_GU`$P#%awet_Ju z3KjN5twifKGAz$vry@k&R019x*$tzg)uO64OGGeoX^S9()mhj$M}~g)Zi6qEPiH{v zzeYkf=4lveg5L8qoeRz8LJs3G;6jpr|2cta<%~zLU&9axUpJ!(_y72ABr!l{GYs^@< z2^vQl95yF%NjE&%cIZ|6uxPLh*Sx+Ba&;8cX*P0jEJ!rOBPUb@N5)c&Y%>=d*axs`PZE;!3Vd|OWDK8lI}Rnr z!W6d_-)vZqL$(4O)_jYVR}4k}d$u4~`!ycA{YuQ3eKGdN#UK)NAoWl@)~@>;TAu@Z zUYdoDldixag&Bn|HJ)40AFX8PVu$-EHRgKA)1StoyFY|VnFFhD7c9mU_$*d3Hp$ek zgwLFrS9b)3p)`~?G$JqCf&I^pMwb~I;0ZO66I2UZ+9!xttI3VUG)jvq$6N=L8bo~xAo|SMNu{cP4QTFX)lagwHq$43ISy@5@M*S6BNlFAr0W#et+%kVS`i%Pk9@J3zYNYPkiGtip96gbT zOcofZ72CPQ8n@_3P?OSNLYv;XH6xY+lkaFI=(g) zvCqyy>p{=Mz?03?YO#I$cI1*dYdA`6-beE>Y}`OBj&063ugKkj8AFHT@g2udLf5U_ zbs`Z0!r&xo>zOtjdq?($AFmj`euvZl#_oyDJFHFaX-j`v24wY5gfb5c5 zgpT@A<~xdGzVC2Ln|63G)sNsYIu8|BLzly2&xk<)3H5d2mBAmdoIaSRQ6-4+9*_8v zvGSaD=+b={W-Z?Ur^^qseIGu%s*4zwVZzPpVbsN9+cN_&ZZ5UmB`)O4WAN@%oi9WC*^42!A4dB2 zML4H(dz?G}e(Xz%Lq^Q!7~69w9{l2aI5os~)@~8Ar)L_?(5#<}a|chw2m5l6lC&KC z`wYj@_ddh-Y6Z%ivDo_IIz*>$L7HL@9_Zg4w|{&PJ`X*o1Fwk;^>GV!343Ft``GsQ z)mVMNOuBV?XQ*AZ6Y6QpN zGDJ*-V3F%!$=Z%bhqb|F%fExhdI0uR4Xj2T6wUzoqAEBJtU|9rQ?TSS1;Rf*gK2|X zHy?v%zlnq9LvZf91A}_c!$u`>ptN+l z_HDRgK!3cjD+6+i8kx>Se1CBlocoT0p2s1WzrK&IWd=Uo^ds!vSm=`tSpVhsh*4`1 zzwtJ7>2@(v+#%#RO^_>o#HvYsG5zDcI7)mW=AE0-zuV0?kiHvA;x~aDGj41z!*lDC zp)~D>BJoW;AnSl04{buCMGMR4)6i<{>a!cn%W|5LpeBcX+DJU~Toe>RH_}2ba%iHk zEb)41`H8z5`d z6&+}wVZ-|2kt-)*cL>m%EpY1+$YBV;txiB75P(aY2D^F>t{&V9cdt)_-{(TMG7@gXs^w6CKHA1cfxR6NtYdiKsrz2s`RN>PLMq|>m>tRbd zh$Gg$c=4?l#DMs+j$JUgTU%T+|0=}U4G5>~!uf-G;ii{g6xkMM3g)4y*)^}`H~@E} zAqRv50NrR?zi!;UqoW{-(-)p2fU$Vmws@}cZr;NW)LGoQN%$uNlOrf>IIc;WjTa#HAmh(u=ZJXa`oyVgYRIa{!` zjD8Qp3q~T7v_n;7H&$FU6m7{t?jY-d9_QYKk5$Kr;?Utoqw)CMA?Vhs4O-E0J%?V7 z#hdInE<8zo%UqAb#P@J5k@j{Z&>coyiMNwWP|XjHyejTW+ivP7Kg|mI^QC#)FT2^+ z2R_8q4ioW?PlOu({N*&kJdZ^QvoQr;mmDtjK3q4p1Lm*z23}IwtdJe%panZ0JqKN; z-H7OTH(VMoa*`g#@bOcqF1w?1D;XwFn29fbh(U75iJ-Lt{{8phvatgp>pqz3q60d1 zk>UQ!&O^K(aQF-`nhiMY)KkNmM(0n&-NW0E91llFa>_cl?TNNjkHaPp#lZs!aP4>$ z(}v!MH{?puSO47wb1fv zcpf%?>x9Ok!@+~gFmp1?#&D9Mwz%!W33xvy9Y=$^;MDKK6U!eHV+8Vm;6wTj!IMwC zfDD}*KFwEnYVi^b8Quqz$4tY+_g#!(eWzo~PHIbRP8i<50ImC8jqi+VF-E4J^vvPl z0a{7l?UpkJ^Tbb{P=dbH;wao}W}wfxn~=p(ITAnL+B-3-AL$C+kE~TcOuy}Qq!x1b zLlP)HxSPCaqAq7qF!Dn1=@IQ|vPAKhK(Sm!Y} z;H`urcC$z-s&F!}7fUZ4B-*w%^o)AUxD6j@*_EdP8_JvGgdC_MXI`9wvnu}K%kK^5 zS)D5EzGt!sNZj|G3I*;W5!{Gde<`)WU2);_U&H8*z?l9u?w)-C`izlb*0>RPcZAC(iLYyR<#b1-)H8Zj$1 zkN;)Z{siWXxewo_>_MqzCv@@KF!#1A(7P+kstl9H&cb`|Z$mJYiqF?A!q6UrkQA$j z*_{TbKOHV}_{_n)+H&!1kJp{VkI&yB#xUzg+q-q@Ogb?XGaubcqRy{>j=+1|CH6(> zcFZO_@QR#O=oqayh97UgvAJu0f3h##=i#Bpz7d1zb37opWe~MLL(oyy7qYHoTc~_l zt8?+CjzbV9q5EVZ+0;?AjqOV(+;Ge7(B%T$p}ny*0ZT6$Om)>39on=;yV0}p_;>c^ znLjyjxAh{SPcpVk^h~&o=^z`2m9`p^j7C%hw&JPFhLXK(OZ#*{@0mB@OD$;^Iox$+ zX;^XIV6<)DMwHQE$YogZV?fwaG0QKJ)PlrUaosSsbzRYV{CvETkSW>?eh&V(N2BxP zwQviutVH_Csl;tMh&FEUMNeU)qAI$SP zt+2S2Fll4(-fd&hz2h`I@#7wNjCT0^T4+DLRm|u*fB9Bevdu8;_z>4!FacwGkH&z> zqjA@D<1wMnjrckvi{$=$+%};rmTlMuZ^(nV_ot%Qh=-ssI#84ufL^DBK^~1j$P3f@ z8zJk|4XwG(I<{+;iOw>-vUWQR>U6wtT|ZpAY&}w3DKPGT1=GiM#f-MCFk$xPxNynU z7}t9_(o^DL-u(;)_P-d5pS%L2`^ZFB(p&HT2y&wm9?v1XdChd8`(0#{iFZuFRWB}w z+-*Xk-G#)jZo}2%dZR4|`@40(1+#9%2Rrmg%?}~8X)!JxGy(m`kHGZv?#7af`l8DN zUs5}xM@VxJj|?Qc{8n7E<3hT{obS|ZfX&X3k({BQI3O)e!~=N|I`==8CfME^gWj{Z zAV+K}hJWpSm^6@Q%wu`(gXy=vg@mF8+LMHc{HGHnYo*)fq1(V`p=9&X#GPWRg-o8T zjKeMMyW#F+*6SuzN4~=?#QB(4$-0lg^>3?CTGvR$aIl*+DCJJHr}MOKMcZ4qYu2SH zA0xz^=9iZ$E&sOscXdj^JP8sc{LyGR?()as%)z|kBF_D0`_+t-iAG$p=2e(wQ=he{?g9xo%Wj z14w?FeBa?0<6ue#;@+ExArtSy&DSkJ2eMPMMs~&WwOgSzImoZ1@@?C3*P@#-n*2AO zIlgs|5qS8CjZpZMNPTBGhR=KsrjQ?YRSbN@%@4eK5BiL~4;ju3I1W97!F{J8&Zb78 zCjz~86Xp%+jd!*sL19wDWl6xRvwLCcli$Iwi$kVhSQPl3NOI|6Pq4sZ@}ohnh1Hu5MQ(r`^Z-(+;+=K{GBZ*UF@+EghT!ui z!$3|_z?cAK)-lnKm^wv1zO(YS4rlQktW@y|zkZF`(ASukYE15xP_*!V^GA9XV8$&4Z2e+gZ*=DlKmk z-wDzOi%bRFmUoy-wkc)6=$4zHwrIN)*eBs0x&lyRRbK8ztoC@MrFUqfvJb5rsp zLxQB%()mP|0zni*>jjDvtBu@SZET;+Pd95mBhRozpr6TA|L#{ai>Tngj)M)C| zX)xHMaoCgqgU^S|RF9aI(-eq@*Kb7Fpn*L=jiMzJHj-6nv$upc2Og1BL~imP#_b21L>lQ zoV#K@a-B|Od7>e=DnvI{pT&=yKt7Zf4a$OMyfIORJ_|oY(3%LZD-&i-3bLF5C~P+P zLq-I3NeH%s7fIRk969Q zkL+L&CJx3p5?~1g=v?Wr8WnK)-E?m@WQQH3zsd00)zItZXU@#4spLdWF;tQ0Dqd^vUZ9y~@w`4J&+BHOdcP3uTENZUALPblh%BjQxmq+~pH z7Vmtb&Mh{btdG!tl0)*nswzlA=^9w{9K0Xtc11nuD4i>}E+XWY)#503Q{)3UgO~o; zN%-kj{?W_t4dw+rUij6!k#3GbzN>%?G}#%G8Vc*TFlX55dopr^HpGR(RL&uof>}fm zywEx`kxzPK^tzGd*TStxhT3I@Mj=O``ydRiFv%b3H|eRL46cLZ&|@&bY)eMOYekhe z78*wp(#SsL`psfMVY6jFG8Jh^59Cr?ph2Z05o&J`7ONe4vVR4>WT-TBKGG*MwFwbd zGE7Pxj9GHz6X^;V9k6?I5wd$>cP7K-ks~=R9)(!}x@OX0A|=_`elgsHLXjaR9XMk! zub%XSo}y5RTCb2tF(713k&u6$qp0EdQ8pJs#yN3JOj|()pn~^qs6d#vk%*U^;E7&H z_A8FzI5qPebl^!QxI3+oWfpItb7V7)ghe*GIA5t>w8gb36E=(WK{VSY2T@M?$KMN&6jNKkcSdKT z{l$5XdW2Qt72<6e)n?vV4mM*c#gsvPJt(ycwepq;k*O{%vxyN7G$~7 z5LU!P@6JVv-jCzdE}N-6ce?Y)#vDLFK?qr13$z9+sxvl2McgY)*OQ{oK%Uh_Ja7-Z zMAAdyYy>TPpi+fUXt5Ka^&sR8BcyTCvFQjNO~Wyr4JlbEuB#UeV%DLd0Ji#G3qm}i(iPedeJi-HAayuX` zr(Hz7ibV?MNsu7nk4DRJmp=}tw_int`9y*0kd+xmBpgIxL7oWQ<>%#yZKb89B4e*0 zKUZYt@tgvuy4gC&C$({J#$X!q(|5y2zNg0)NBq?ckJk@J?h#mm4iuUXAz(5QS3Zb5 zt)FA~q!sy)+T+C%r&!TY&srDo?G1swf1L!$CG!hayEH+}TbjO?p~qL6H1z zw=x!1ha5qz1{!ZBQpg|8^|@d*%TZ$94|}MLd}9OoopHp6e8g4KVMsHPpPq^=V-i&M z9J*#3d~Ov=tSL~Mo3E+LYr-CLDvI?cMBF}TZRv13UC^3zDDWJD#SnzuAA}}75s{z{ zIcfV~3Ma$w%_BZv3QdLqha)?PZ_)D(c#u!LtI*+xCh14w`1vqsTu9H6!(&cECHVj< zlb`D6m-6tR;a3IoO7syZj2e{q)g%N-$kHou)a^owGal&}D0Ri3mC^1~FcV zh0e)>$lWI_J~KHo$*}l!@Or(-FTr;VBTsB_#>_l& z&N!89#v? z+mq}_l@nQGqDQN%Pt>E9%4bf|NUlV6AvsF*{Fe3@I55X;U3XNI&9kP5BB584(20hk zR6}op(2I1GB1Ax%^b(O?rGwI|bm;*R0RKw(<>~iTQ48^6-QE?=&&9gQI|P>;(ehS z)r9#P2M<*jq1zn(#gID~m;sj>Y~H%{=+^yJ^v*Uae{mM^D}m&+XB-_uA^)B|H#yGd zDzE6`#&6b^~Qu`@$Ma?o~i^Wz#0%a zry_2TxVaU@C&Z#sdNt%F1vL0UV;~r=DV|$5s61N`W0DXHVp2H%ia>Q>vEeg}7L{&; zq+^^~T$)hbmXzqh^*MPz{dDz$yI0&Gz8uSw{3;D;rPqd%!sdw!w1GuSRHbI*=J1sI zy+_P&J<4l~Q+BMXEc&s1D2?7=dRQ}+&7KXaUG)^d3W4uO!lx*-xTIKRKSC+yH|==k zZii$5Ah7<;gqXX4>L{NE-$P0*@H4IXl#J2Ci`uuUZCcVn zte%gV9Tp4Bk9*kd6vVl#8lVSyEcCN7Dd#|uVp$ZvSHA-WZJ#T6|}Eg~vb>La`T zq<|8E1M^nh3xM*-J*7#xPO729>y4GC;GZMT&_=DJ(AKNBb`S){u$t*)yI$Iwv|Yg5 z6$qARS5jH+{gMHq7wHXIn^PzVVOOJ=u!Uj^nVBtw@p2g@6E!P7fp&fwdfryWLvi6F zwLGd0f*snMJd9?VQQDPpg5r!xsqd(2`uN)yf1V%9AERy%GPJ%}_!Gn6pG^BC>>=-{ zzCG6tJ;%g$H9`zsb$RtB^f3#8PklbaTeEI3D{pD}6*#{#z-Mw6b~Hm`hfcq19~ihl z1X9DFh;nYrKlPmR<<3%b^0@HEv;;|%Y+rjh4U(y4o1BQ-(}PyO+)SDZ^HIDtKM~XJ zR$^9`1h=tPf5pN)Go{>dh!78EG*Ya7))+~+}V?v&ftwdne8>V|aUVSqh%!F2$#0oMIA6p-Mq| zoS)-96tmQh#FbfIkA0`-UOW24w*i#H%Ca5D=JAp?^BjS?P6!vb+40}8*rLSNLGOIg zj?HzmhcI}Ww{pA>oXD_~^!4Yeo#*O{x;Kf}%jG(ZBkpq%!o+FrwAjo>4B#JVnGeKd zcg9nudCXmb8nVX4suci}MpV%1n=`+RsytOzcpw~!s`V;V1vO9IuFF8C6rH66LBQ%X zCxs|fImKKEZDP1C3igBYk*};%m9fx-)av5}mP~i@86`1BMsT`&{XFlTE!U zRE|>)uN=Zer;1!3jc9C3TTh_onb8XNRt7>}C4qT3gTM{9#E|6ITgjOn z)d)U)XaaH4I8vICno4JQP{kmh?I0}uhSB4YN5K(HP3pgvN_zqru;mB3Orhf9HTASv zux2bzON22!VvSX`@XY;QMa;-ck6XHmt4;g1iLGp%A~rA=Uokv8u)CB}HP0b-<~cHX zi9E|l{e0m{o>u(%-5XchnZ=sS8P0~Te~iQl+}Wk+PhS*Ojvq-eA!I-Yz`TDy@V(1! zw))fm4yU&&3}sb!GiPtDAC{WO6l0#loo?HrNW1Gue)hWeVVv4FXwCTQ6pr?%dS`z{ z5?{T0_=GMhbt9st+q0^HV$Dp4@Zl!Prde07`eVw-A)uS3boL(6Ad^u!G1lUGG zb?pQ|FBqy)I`9CZT_24;Gr-qG1VtCpuf-_fukNnh1;oSOFURTgJbzL_sX&C3Bte`C z`||azZEan#3S30P#nqs~cP7mL^S zVKSQ7*_w2Z`ryP9K8^*Cal3h8-JWGk7E#9P3xPOCy}ezfaMa{0M=(SHG6XM-LOW1c zBPmR)SWZ&Oe;!LRv zZ5c&;EA7FHN=gzJpSyuhOc(=Z@7eOR9PGQE^P zup{0#m6T-7H^&rPEfhyq-J=&f^I_37fOp802J7MKzJP31x~rG62O2ij3I z&k7|aql==~yd2HXnb~D(R*J-A@RzpKV~Ap1XDv5zWHO@D{10209z>@4v4*B`7*BI! zcr3o@o273^W;=613K9xhf<-$k!apK=(JLP^JftM2C)&MN+M07crC|VRi<2Qu zIqy^K*0I!g)q~uIylCTVb$}pu8*##$A>@ zNxOI6z3LSp?Ljg!MvUsLo=kFf0N3uDiX60?DSx-=*<;|nb+eBuZ_^X6Q({7vuMtJ! zXc3Q?9T;u=+$`Mw*eWo>gKW>mVuXX&^~Tm@2CYeY_zd@CY4nnV;DmCK<7>)Bc)s>e z_vo3zD>WKGr9C!a&^?o&t#fLIV7h2JtkZmC+@ucLy%-ZY_8{L=hHfP=p0?r&*EUkH zw(#28M#Z~Q>H@KBbE84E?Tp%t&ckbT3!Fa1x@5&#%C5O1j6k;653ahB)GhnxzK9qh zdFb{6IObGw?I@d)1k++3_gMe7jH$^eRmgy9sGEP=6`*68noNtiBs^|AYRT& zYqHLF@-m#;dOH2*X>qAGhevDN5IOOP*{jp5K462i@)8^Ve zL}d#5R4*{9b2snwzWyvtWxQL%yo&sEVxtl_yiG3)CfIeDp|pKsfnYQV8*Bue<9_h- z&gk7GBwLkC(pnD^uVNo9zd}THot_=>iP`_G(S-i`N?T>L#@97NPaZi>lO;sHJ&Z*jkmFf;l#?pCT=%^}~`tlEViu=BIY!EN!i19}5|23H9Dz7kaG!+&z;>GzCKi0gQRbcf7hAR;2D|a<8sT2*i6B5_m@0*FWB16io?=Cy{X|*1iwu-0f2TAln((Pig31zO5|&Je;cJA zma`esC|qD1UE_He17`NOAtSG9V9FsH(bthewxmvK*3*M|BmAMjgt=kE01MPnW3$N} z|MYwT$a?*pE90VRN`}Lf@-InnWVUT&D`ew)(n3SWb%`yZHo;{yb-5Pt_8Iz{iYfrZW*NiTe#^^dL)SEa zy8FlQ57n**S2ykQe=dz#2t)+JS1NYuiGR?q3{|TM=*Ptl1qt|ywwnS|r!ag2>lo5A zUEl{X-~yK?@1?nw<#iNb>=1q&hkU)dwq4x zx*4yIPI8A5!0e3e+Q|lAJn3f&kzr{iDOvRC#M&6L7B>N=k9_#T+B@(&XBy0HZ2KM^ zg`u5ZwDsh|F=k``2 zEM!zvx0K>Hy~0(dU7K5-t&&e~msTFWSNkT#ty7Mu7@^?`5HjiKRhkFn%>$!h;2d8A z4|L|j$VV3eYdN)>4JT_}JT!XK{du?2I5A~DZQ;-~hMy{-di=4fY=}=ID;pqA#x+=` z2P+dvU5R)V5o5WdjN@;f>vit-@w{`T1)8>jr=A~&C_b)#;+3tZDnHJXvyj3UK2t9% z^#$#)u?)}2fQXpcV4@fZt$cG`OPuVvLXUh_e-hvOJP#?Q1PB%BQJ{0{bex_AF}3vx}SK62qF_w7b!+ZD_V2Srlp@SeA!}{%;X%c*w~NF>u9460%*Hx1>p$cVgcTR*luY= z%Lfxf2Zz+;bvE;s=lRijC(iQJ5QdUDn|x=8{qu@sq$c-x1JYFNx8i`v**!5Uk{XVg zhNz|RpPYzu2)dpYcO{T)<-Vm|_IG|Ir7zy0>dc#PZiCM^Y(x(dzb<58i$~~t<_9=B`F#L-?*!1x?0n#Fza+AYk%*k z&CaKcyBNb`P^tn)l2?8pZm^7JtfBM16kT1EMGW6#NYoMdyhCZ>h3LsJUVkEXCU14< z8lU&;F8Y*IFgq!h{y@-3rgt6;Lp&7>>-uIuosC&zQ{?blzt13CkK9Cg1-;wVx z23-A@mD9C^{1J3TxU?L7wwD?a)J3AZIxA)mi2oIF^za)xEo(cLJu3-`&&2;AcVfRF z^Upq&kXvI)cE;_v89DNwdwHfdGaqz#bw2H=xin!@YRD^^c^1_Lh9$E~R_^AR+Mfsm zm%XHOahaJBL0E{FXE;rPCE z{K0(-C#&?FF2+E4?F>;<-|z8c3iiVHM<>3B!Q3m9l(PH7jYhqvY9d)4edNIX?62 z`YSc+jo;My=*f{DdH>AQ5#f|1lc!f%cl7-pq~U*%%}4=!&S({wf-XjPdIHJr z@crRnXdN#(Qs)riDC~6A3m@S%IG+A@hP(p&Gs#B>zbHc@Ngq{yyv*paT&<;95Ih(X z3>ol!@y2C4=)#sXU?mk_6ln|dIuY-(o5E$N)2DpLx(qAhe$0Fr9vV7OzMi7)KP&L* zQESI@*Vo2E?PM=~hq<6EA z#9vuBFueh1Z+cp;u?Bq2jQm19^1ty9`!C)|0| zx^m*mSNBn?FK*HeM-5!NA9p7EPUZ5WYs~rMo5W@8IF2p*PSZrdN61wZgTxKd9SR2c z<`qqw5B~A<+)2C)R`=6SM^%s>mAdV|;~FnbDx$i8xv>)uLd3A3)OpJuxsZ+jrq#El zyZroF3qJ2$Z4)9_X7{QeQ>@z_aKREceT0vCjmC`%t5us%k$q)A%$Pj^XbFq8Qrb% zwl@!;^JT_g&|N#>5-c*17_~&< z5x`#g_6Ry(k{{R6Crc1KVyDPvh{V$JKB##8`!MoK?$jj@l#pneil4{thvziMX4WII zbLu+Z59fKvk3z_2wSERUvVK6lUwYjEVA?Q77+{x}DoH3noetvt50_-Bddc>)FuW@% z0Ko0nkZgocD?yP7j-L;FKN$Lhg=9t!aHRix1MTGWBr@pyjX=&BG~9i%x;u&Tb86D+ zGQoZKGVd-@(xGzV5}BUkqS}BCBTqA$WA)#7uK5XH6#?_D%tX#-8}AKQ>&k7AxFwWj zQH6%y{2+JVXBK$SNGA*!;b^?=*z~7-6WxWA;l}Rs@|`qK|MA;z&iyreI&FzVhDOS= zwGOLy0T*kD3KRi<_Fv4<`zV|EuzpQ48x`*!>&w6}uZz!^1=bh#1 zLSL3d-ovp-J zDUR1qf)3t|4wX<^`KdI$Xig|HVeC!|IM%;^zrZCjSK`E~o{cJ$?&c2%Aht*DV&ra= zE$r~&1|LB*39B^<3>k>MK%W+=6ZB{P{v2a2Sv<4s{xC=XeG6p_ z;dm<3aT=gVX!@_U`uE36mX_mIt3Mt5X}z+aXiIT_RMct%#W*Tx^&)Etcs(2Xw|~O$ zY*lm~)(HGFbjFL(zav;(I?Ik~PWs0l{AaY>jtkHJ2N+=G{{m~>J?L+AoAZ`GT_&lu zXi{AsM{-s8r8vwnB{Z!aAe#aYsD-W0$so3^%tA$0F;H`P{VulEG$gD2_;dBZ;DP;j z89HoV#>wfHb4(44a#EHDphdlyavl7s1D(SGAB~m##-@d;#YOLJVYC}h7)7A9S$2!I z{F`7gR*_CR1K|+FKbY~MSA;SZVgF!E#iyw17*3)6P}YZvk8eQ&zj+9U+FdUU-n9*MSrK38ICkvp zMDy4L`pQ6pgUQX_97wV*J|Zo=dwi|Xx|O~rQ~pU`g7dGz{)2A5AItFqDJy9LbPjz_ zkd3*6p>}f;f!+tCfj>*~dJlxmh5Ks~_ObR>A9QqjUN2Fn<-}$v`%P0xN`0LCp)vK* zWEEu${#~!~*!me|D)Dz`S<9r{TnD8(SH@71mc1Xv)fZ8xwbk{-J|8E3P#l1LFKoZf zGk)E19j|tHblR!^a}hM`Gq1~=&2}KS(v zO|vV0pXkS--ELlCS+*1#7fiT(X$6*PvW^kTSMMle^~k&CiDK2Mxb~KtzA{Kxs;uaR zE!M{N2=SsM`ARNyDTTfP@7>HRWQnXO**EwgaHH(>%{wffb1iuG+w|Vs42N>d zzLxh^0Lq)+=cOp;m?=-sJ#)7@)JPLVsr)N}kSSi`DgR~&mJ6& zu)`tT5uxfCBJL@R9#<5i*SBoLH>mnyk;Rwl6FEje2C!5{k?G|dSmuUg|debdt^93bolh&SKmQHvc8Zku8jzrQ1SMb~{e?!CNU zJew1*8%tag#vqM^xi|CJ-@-cRhZ}_w>1R>+CtM8)5FML}inEBSD 3-clause. See license attached - http://www.intel.com/realsense + http://www.ros.org/wiki/RealSense Rajvi Jingar Reagan Lopez + Matt Hansen catkin roscpp From 8065ac3b2c7974fdfba819708af9c1ac304882db Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Mon, 29 Feb 2016 11:24:17 -0800 Subject: [PATCH 046/124] Updated readme to remove the settings unit test file because it does not work. --- camera/README.md | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/camera/README.md b/camera/README.md index 1e9b549837..333fb892a8 100644 --- a/camera/README.md +++ b/camera/README.md @@ -245,15 +245,14 @@ Using rosrun command Sample test files are available in test directory +realsense_r200_rgbd.test + realsense_r200_color_only.test realsense_r200_depth_only.test realsense_r200_resolution.test -realsense_r200_settings.test - -realsense_r200_rgbd.test Both of these methods first starts "RealsenseNodelet" for Intel® RealSense™ R200 (DS4) camera and then executes all the unit tests. From a0afa79496d3c58a8d37c9d9be8e7467e1d31774 Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Mon, 29 Feb 2016 11:42:55 -0800 Subject: [PATCH 047/124] Updated the website link, version and license in the turtlebot package.xml file --- camera/navigation/turtlebot/package.xml | 9 ++++----- 1 file changed, 4 insertions(+), 5 deletions(-) diff --git a/camera/navigation/turtlebot/package.xml b/camera/navigation/turtlebot/package.xml index 86d6eab394..ba069d974e 100644 --- a/camera/navigation/turtlebot/package.xml +++ b/camera/navigation/turtlebot/package.xml @@ -1,14 +1,14 @@ realsense_navigation - 0.0.1 - Intel(r) RealSense(tm) Technology package allowing the use of the R200 camera with the navigation stack + 1.0.0 + RealSense Camera package allowing access to Intel 3D cameras and advanced modules Amit Moran - See license attached. + BSD 3-clause. See license attached - https://github.com/PercATI/RealSense-ROS + http://www.ros.org/wiki/RealSense Amit Moran @@ -18,5 +18,4 @@ roscpp rospy - From 01d0ee9c1fac7ec108cb97f5e824d363bf377208 Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Mon, 29 Feb 2016 15:54:40 -0800 Subject: [PATCH 048/124] Updated README with correct settings information. Removed settings launch and test file from repo. --- camera/README.md | 39 +++------- ...se_r200_nodelet_standalone_settings.launch | 75 ------------------ camera/test/realsense_r200_settings.test | 78 ------------------- 3 files changed, 11 insertions(+), 181 deletions(-) delete mode 100644 camera/launch/realsense_r200_nodelet_standalone_settings.launch delete mode 100644 camera/test/realsense_r200_settings.test diff --git a/camera/README.md b/camera/README.md index 333fb892a8..46959655a1 100644 --- a/camera/README.md +++ b/camera/README.md @@ -28,8 +28,6 @@ Sample launch files are available in camera/launch directory realsense_r200_nodelet_standalone_manual.launch -realsense_r200_nodelet_standalone_settings.launch - ### Intel® RealSense™ R200 Nodelet Publishing stream data from the Intel® RealSense™ R200 (DS4) camera @@ -72,7 +70,7 @@ Infrared2 camera rosrun tf tf_monitor -####Parameters +#### Static Parameters mode (string, default: preset) Specify the mode to start camera streams. Mode comprises of height, width and fps. @@ -89,36 +87,21 @@ Infrared2 camera Specify the color camera FPS depth_fps (int, default: 60) Specify the depth camera FPS - enable_depth (bool, default: 1) - Specify if to enable or not the depth camera. 1 is true. 0 is false. - enable_color (bool, default: 1) - Specify if to enable or not the color camera. 1 is true. 0 is false. - enable_pointcloud (bool, default: 1) - Specify if to enable or not the point cloud camera. 1 is true. 0 is false. + enable_depth (bool, default: true) + Specify if to enable or not the depth camera. + enable_color (bool, default: true) + Specify if to enable or not the color camera. + enable_pointcloud (bool, default: true) + Specify if to enable or not the point cloud camera. + enable_tf (bool, default: true) + Specify if to enable or not the transform frames. camera (string, default: "R200") Specify the camera name. - Supported options: Here are r200 camera supported options that can be set - COLOR_BACKLIGHT_COMPENSATION : [0, 4] - COLOR_BRIGHTNESS : [0, 255] - COLOR_CONTRAST : [16, 64] - COLOR_EXPOSURE : [0, 0] - COLOR_GAIN : [0, 256] - COLOR_GAMMA : [100, 280] - COLOR_HUE : [-2200, 2200] - COLOR_SATURATION : [0, 255] - COLOR_SHARPNESS : [0, 7] - COLOR_WHITE_BALANCE : [2000, 8000] - COLOR_ENABLE_AUTO_EXPOSURE : [0, 0] - COLOR_ENABLE_AUTO_WHITE_BALANCE : [0, 1] - R200_LR_AUTO_EXPOSURE_ENABLED : [0, 1] - R200_LR_GAIN : [100, 1600] - R200_LR_EXPOSURE : [0, 333] - R200_EMITTER_ENABLED : [0, 1] + Supported options: Following are the options supported by the R200 camera: R200_DEPTH_CONTROL_PRESET : [0, 5] R200_DEPTH_UNITS : [1, 2147483647] R200_DEPTH_CLAMP_MIN : [0, 65535] R200_DEPTH_CLAMP_MAX : [0, 65535] - R200_DISPARITY_MULTIPLIER : [1, 1000] R200_DEPTH_CONTROL_ESTIMATE_MEDIAN_DECREMENT : [0 - 255] R200_DEPTH_CONTROL_ESTIMATE_MEDIAN_INCREMENT : [0 - 255] R200_DEPTH_CONTROL_MEDIAN_THRESHOLD : [0 - 1023] @@ -135,7 +118,7 @@ Infrared2 camera To get supported camera options with current value set. It returns string in options:value format where different options are seperated by semicolon. -####Dynamic Reconfiguration +####Dynamic Parameters List of dynamically configurable camera options: COLOR_BACKLIGHT_COMPENSATION diff --git a/camera/launch/realsense_r200_nodelet_standalone_settings.launch b/camera/launch/realsense_r200_nodelet_standalone_settings.launch deleted file mode 100644 index 1f889ee666..0000000000 --- a/camera/launch/realsense_r200_nodelet_standalone_settings.launch +++ /dev/null @@ -1,75 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/camera/test/realsense_r200_settings.test b/camera/test/realsense_r200_settings.test deleted file mode 100644 index c74383f288..0000000000 --- a/camera/test/realsense_r200_settings.test +++ /dev/null @@ -1,78 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - From 4afa456425230da5158f88c10a26044baef91756 Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Mon, 29 Feb 2016 16:09:52 -0800 Subject: [PATCH 049/124] Added global readme file. --- README.md | 9 +++++++++ 1 file changed, 9 insertions(+) create mode 100644 README.md diff --git a/README.md b/README.md new file mode 100644 index 0000000000..610271fd88 --- /dev/null +++ b/README.md @@ -0,0 +1,9 @@ +# Intel® RealSense™ ROS +These are packages for using Intel RealSense cameras with ROS. + +www.intel.com/realsense + +www.ros.org + + +Refer to the README.md file within each package for more details. From 0e12ea693ed97d2e60cd8dc8350592ce0323bdad Mon Sep 17 00:00:00 2001 From: Mark D Horn Date: Wed, 2 Mar 2016 18:47:45 -0800 Subject: [PATCH 050/124] Update ignore file to Team Standard This is the default file for ROS from GitHub.com plus a few team specific updates. See Team Wiki: https://wiki.ith.intel.com/download/attachments/559551949/ROS_gitignore.txt?api=v2 --- .gitignore | 49 +++++++++++++++++++++++++++++++++++++++++++------ 1 file changed, 43 insertions(+), 6 deletions(-) diff --git a/.gitignore b/.gitignore index 1f5220ba76..ed29d1381c 100644 --- a/.gitignore +++ b/.gitignore @@ -1,15 +1,52 @@ -# git ls-files --others --exclude-from=.git/info/exclude # Lines that start with '#' are comments. # See http://git-scm.com/docs/gitignore -# Don't check in Top Level CMakeLists.txt -/CMakeLists.txt +build/ +bin/ +lib/ +msg_gen/ +srv_gen/ +msg/*Action.msg +msg/*ActionFeedback.msg +msg/*ActionGoal.msg +msg/*ActionResult.msg +msg/*Feedback.msg +msg/*Goal.msg +msg/*Result.msg +msg/_*.py -# Ignore all Linux Editor revision save files -*~ +# Generated by dynamic reconfigure +*.cfgc +/cfg/cpp/ +/cfg/*.py + +# Ignore generated docs +*.dox +*.wikidoc -# Ignore all hidden files +# eclipse stuff .project .cproject .settings +# qcreator stuff +CMakeLists.txt.user + +srv/_*.py +*.pcd +*.pyc +qtcreator-* +*.user + +/planning/cfg +/planning/docs +/planning/src + +# Ignore all Linux Editor revision save files +*~ + +# Emacs +.#* + +# Catkin custom files +CATKIN_IGNORE From b95f8560e8285e35763dcb27dd7245aee5735240 Mon Sep 17 00:00:00 2001 From: Mark D Horn Date: Wed, 2 Mar 2016 18:35:07 -0800 Subject: [PATCH 051/124] Add missing Change Log history file This is a required file as part of the ROS (bloom) release process which was missed from our initial release. --- camera/CHANGELOG.rst | 8 ++++++++ 1 file changed, 8 insertions(+) create mode 100644 camera/CHANGELOG.rst diff --git a/camera/CHANGELOG.rst b/camera/CHANGELOG.rst new file mode 100644 index 0000000000..9a7d041a27 --- /dev/null +++ b/camera/CHANGELOG.rst @@ -0,0 +1,8 @@ +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +Changelog for package realsense_camera +^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ + +1.0.0 (2016-02-29) +------------------ +* Initial Release +* Contributors: Rajvi Jingar, Reagan Lopez From e6c2093f032a1f6fa7204fa3860710c4c3cc2a82 Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Thu, 3 Mar 2016 16:27:36 -0800 Subject: [PATCH 052/124] RAR-258 Add rgbd_launch as run dependency. --- camera/package.xml | 17 +++++++++-------- 1 file changed, 9 insertions(+), 8 deletions(-) diff --git a/camera/package.xml b/camera/package.xml index 292d330119..031f6a3db9 100644 --- a/camera/package.xml +++ b/camera/package.xml @@ -13,34 +13,35 @@ Rajvi Jingar Reagan Lopez - Matt Hansen + Matt Hansen catkin roscpp - nodelet + nodelet cv_bridge image_transport camera_info_manager tf message_generation - std_msgs - sensor_msgs + std_msgs + sensor_msgs rostest pcl_ros dynamic_reconfigure roscpp - nodelet + nodelet cv_bridge image_transport - camera_info_manager + camera_info_manager tf message_generation - std_msgs - sensor_msgs + std_msgs + sensor_msgs rostest pcl_ros dynamic_reconfigure + rgbd_launch From 3e9684d68698cd54f086fd3bebd175677b2694b7 Mon Sep 17 00:00:00 2001 From: Matthew Hansen Date: Fri, 4 Mar 2016 10:47:21 -0800 Subject: [PATCH 053/124] Add identity matrix for rotation to camera_info msgs --- camera/src/realsense_camera_nodelet.cpp | 11 +++++++++++ 1 file changed, 11 insertions(+) diff --git a/camera/src/realsense_camera_nodelet.cpp b/camera/src/realsense_camera_nodelet.cpp index ccab900bcc..361163cdac 100644 --- a/camera/src/realsense_camera_nodelet.cpp +++ b/camera/src/realsense_camera_nodelet.cpp @@ -397,6 +397,17 @@ namespace realsense_camera camera_info_[stream_index]->distortion_model = "plumb_bob"; + // set R (rotation matrix) values to identity matrix + camera_info_[stream_index]->R.at(0) = (double) 1; + camera_info_[stream_index]->R.at(1) = (double) 0; + camera_info_[stream_index]->R.at(2) = (double) 0; + camera_info_[stream_index]->R.at(3) = (double) 0; + camera_info_[stream_index]->R.at(4) = (double) 1; + camera_info_[stream_index]->R.at(5) = (double) 0; + camera_info_[stream_index]->R.at(6) = (double) 0; + camera_info_[stream_index]->R.at(7) = (double) 0; + camera_info_[stream_index]->R.at(8) = (double) 1; + for (int i = 0; i < 5; i++) camera_info_[stream_index]->D.push_back (0); } From 5d6488715ce71f2a3a0d93be67e7fcc57b525868 Mon Sep 17 00:00:00 2001 From: Matthew Hansen Date: Fri, 4 Mar 2016 13:26:59 -0800 Subject: [PATCH 054/124] update tests to check for rotation identity matrix --- camera/test/realsense_camera_test_node.cpp | 50 ++++++++++++++++++++++ camera/test/realsense_camera_test_node.h | 5 +++ 2 files changed, 55 insertions(+) diff --git a/camera/test/realsense_camera_test_node.cpp b/camera/test/realsense_camera_test_node.cpp index 7f84367a89..7cfccd9e01 100644 --- a/camera/test/realsense_camera_test_node.cpp +++ b/camera/test/realsense_camera_test_node.cpp @@ -59,6 +59,13 @@ void imageInfrared1Callback(const sensor_msgs::ImageConstPtr & msg, const sensor inf1_caminfo_height_recv = info_msg->height; inf1_caminfo_width_recv = info_msg->width; inf1_dmodel_recv = info_msg->distortion_model; + + // copy rotation matrix + for (unsigned int i = 0; i < sizeof(info_msg->R)/sizeof(double); i++) + { + inf1_caminfo_rotation_recv[i] = info_msg->R[i]; + } + infrared1_recv = true; } @@ -89,6 +96,13 @@ void imageInfrared2Callback(const sensor_msgs::ImageConstPtr & msg, const sensor inf2_caminfo_height_recv = info_msg->height; inf2_caminfo_width_recv = info_msg->width; inf2_dmodel_recv = info_msg->distortion_model; + + // copy rotation matrix + for (unsigned int i = 0; i < sizeof(info_msg->R)/sizeof(double); i++) + { + inf2_caminfo_rotation_recv[i] = info_msg->R[i]; + } + infrared2_recv = true; } @@ -122,6 +136,12 @@ void imageDepthCallback(const sensor_msgs::ImageConstPtr & msg, const sensor_msg depth_caminfo_width_recv = info_msg->width; depth_dmodel_recv = info_msg->distortion_model; + // copy rotation matrix + for (unsigned int i = 0; i < sizeof(info_msg->R)/sizeof(double); i++) + { + depth_caminfo_rotation_recv[i] = info_msg->R[i]; + } + depth_recv = true; } @@ -180,6 +200,12 @@ void imageColorCallback(const sensor_msgs::ImageConstPtr & msg, const sensor_msg color_caminfo_width_recv = info_msg->width; color_dmodel_recv = info_msg->distortion_model; + // copy rotation matrix + for (unsigned int i = 0; i < sizeof(info_msg->R)/sizeof(double); i++) + { + color_caminfo_rotation_recv[i] = info_msg->R[i]; + } + color_recv = true; } @@ -227,6 +253,12 @@ TEST (RealsenseTests, testColorCameraInfo) EXPECT_EQ (color_width_recv, color_caminfo_width_recv); EXPECT_EQ (color_height_recv, color_caminfo_height_recv); EXPECT_STREQ (color_dmodel_recv.c_str (), "plumb_bob"); + + // verify rotation is equal to identity matrix + for (unsigned int i = 0; i < sizeof(ROTATION_IDENTITY)/sizeof(double); i++) + { + EXPECT_EQ (ROTATION_IDENTITY[i], color_caminfo_rotation_recv[i]); + } } } @@ -274,6 +306,12 @@ TEST (RealsenseTests, testDepthCameraInfo) EXPECT_EQ (depth_width_recv, depth_caminfo_width_recv); EXPECT_EQ (depth_height_recv, depth_caminfo_height_recv); EXPECT_STREQ (depth_dmodel_recv.c_str (), "plumb_bob"); + + // verify rotation is equal to identity matrix + for (unsigned int i = 0; i < sizeof(ROTATION_IDENTITY)/sizeof(double); i++) + { + EXPECT_EQ (ROTATION_IDENTITY[i], depth_caminfo_rotation_recv[i]); + } } } @@ -320,6 +358,12 @@ TEST (RealsenseTests, testInfrared1CameraInfo) EXPECT_EQ (infrared1_width_recv, inf1_caminfo_width_recv); EXPECT_EQ (infrared1_height_recv, inf1_caminfo_height_recv); EXPECT_STREQ (inf1_dmodel_recv.c_str (), "plumb_bob"); + + // verify rotation is equal to identity matrix + for (unsigned int i = 0; i < sizeof(ROTATION_IDENTITY)/sizeof(double); i++) + { + EXPECT_EQ (ROTATION_IDENTITY[i], inf1_caminfo_rotation_recv[i]); + } } } @@ -358,6 +402,12 @@ TEST (RealsenseTests, testInfrared2CameraInfo) EXPECT_EQ (infrared2_width_recv, inf2_caminfo_width_recv); EXPECT_EQ (infrared2_height_recv, inf2_caminfo_height_recv); EXPECT_STREQ (inf2_dmodel_recv.c_str (), "plumb_bob"); + + // verify rotation is equal to identity matrix + for (unsigned int i = 0; i < sizeof(ROTATION_IDENTITY)/sizeof(double); i++) + { + EXPECT_EQ (ROTATION_IDENTITY[i], inf2_caminfo_rotation_recv[i]); + } } } diff --git a/camera/test/realsense_camera_test_node.h b/camera/test/realsense_camera_test_node.h index e2e9a5be8b..5e9dc5c6aa 100644 --- a/camera/test/realsense_camera_test_node.h +++ b/camera/test/realsense_camera_test_node.h @@ -66,6 +66,7 @@ const char *DEPTH_DEF_FRAME = "camera_depth_frame"; const char *COLOR_DEF_FRAME = "camera_rgb_frame"; const char *DEPTH_OPTICAL_DEF_FRAME = "camera_depth_optical_frame"; const char *COLOR_OPTICAL_DEF_FRAME = "camera_rgb_optical_frame"; +const double ROTATION_IDENTITY[] = {1, 0, 0, 0, 1, 0, 0, 0, 1}; //utest commandline args int color_height_exp = 0; @@ -124,12 +125,16 @@ std::string color_encoding_recv; // Expected color encoding. int depth_caminfo_height_recv = 0; int depth_caminfo_width_recv = 0; +double depth_caminfo_rotation_recv[9] = {0}; int color_caminfo_height_recv = 0; int color_caminfo_width_recv = 0; +double color_caminfo_rotation_recv[9] = {0}; int inf1_caminfo_height_recv = 0; int inf1_caminfo_width_recv = 0; +double inf1_caminfo_rotation_recv[9] = {0}; int inf2_caminfo_height_recv = 0; int inf2_caminfo_width_recv = 0; +double inf2_caminfo_rotation_recv[9] = {0}; std::string inf1_dmodel_recv; std::string inf2_dmodel_recv; From 4ecbae16b18fd00086885077476ed87d314b06a2 Mon Sep 17 00:00:00 2001 From: Matthew Hansen Date: Mon, 7 Mar 2016 15:46:01 -0800 Subject: [PATCH 055/124] change arrays to use at(#) instead of [#] consistently --- camera/src/realsense_camera_nodelet.cpp | 40 ++++++++++++------------- 1 file changed, 20 insertions(+), 20 deletions(-) diff --git a/camera/src/realsense_camera_nodelet.cpp b/camera/src/realsense_camera_nodelet.cpp index 361163cdac..11d1b5a656 100644 --- a/camera/src/realsense_camera_nodelet.cpp +++ b/camera/src/realsense_camera_nodelet.cpp @@ -374,26 +374,26 @@ namespace realsense_camera camera_info_[stream_index]->width = intrinsic.width; camera_info_[stream_index]->height = intrinsic.height; - camera_info_[stream_index]->K.at (0) = intrinsic.fx; - camera_info_[stream_index]->K.at (2) = intrinsic.ppx; - camera_info_[stream_index]->K.at (4) = intrinsic.fy; - camera_info_[stream_index]->K.at (5) = intrinsic.ppy; - camera_info_[stream_index]->K.at (8) = 1; - - camera_info_[stream_index]->P[0] = camera_info_[stream_index]->K.at (0); - camera_info_[stream_index]->P[1] = 0; - camera_info_[stream_index]->P[2] = camera_info_[stream_index]->K.at (2); - camera_info_[stream_index]->P[3] = 0; - - camera_info_[stream_index]->P[4] = 0; - camera_info_[stream_index]->P[5] = camera_info_[stream_index]->K.at (4); - camera_info_[stream_index]->P[6] = camera_info_[stream_index]->K.at (5); - camera_info_[stream_index]->P[7] = 0; - - camera_info_[stream_index]->P[8] = 0; - camera_info_[stream_index]->P[9] = 0; - camera_info_[stream_index]->P[10] = 1; - camera_info_[stream_index]->P[11] = 0; + camera_info_[stream_index]->K.at(0) = intrinsic.fx; + camera_info_[stream_index]->K.at(2) = intrinsic.ppx; + camera_info_[stream_index]->K.at(4) = intrinsic.fy; + camera_info_[stream_index]->K.at(5) = intrinsic.ppy; + camera_info_[stream_index]->K.at(8) = 1; + + camera_info_[stream_index]->P.at(0) = camera_info_[stream_index]->K.at(0); + camera_info_[stream_index]->P.at(1) = 0; + camera_info_[stream_index]->P.at(2) = camera_info_[stream_index]->K.at(2); + camera_info_[stream_index]->P.at(3) = 0; + + camera_info_[stream_index]->P.at(4) = 0; + camera_info_[stream_index]->P.at(5) = camera_info_[stream_index]->K.at(4); + camera_info_[stream_index]->P.at(6) = camera_info_[stream_index]->K.at(5); + camera_info_[stream_index]->P.at(7) = 0; + + camera_info_[stream_index]->P.at(8) = 0; + camera_info_[stream_index]->P.at(9) = 0; + camera_info_[stream_index]->P.at(10) = 1; + camera_info_[stream_index]->P.at(11) = 0; camera_info_[stream_index]->distortion_model = "plumb_bob"; From 6f0f1d3c044bec7f67bd0e64e0d56bca91d0f11b Mon Sep 17 00:00:00 2001 From: Matthew Hansen Date: Mon, 7 Mar 2016 17:19:17 -0800 Subject: [PATCH 056/124] add depth to color translation to projection matrix --- camera/src/realsense_camera_nodelet.cpp | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/camera/src/realsense_camera_nodelet.cpp b/camera/src/realsense_camera_nodelet.cpp index 11d1b5a656..f5a64d4997 100644 --- a/camera/src/realsense_camera_nodelet.cpp +++ b/camera/src/realsense_camera_nodelet.cpp @@ -395,6 +395,16 @@ namespace realsense_camera camera_info_[stream_index]->P.at(10) = 1; camera_info_[stream_index]->P.at(11) = 0; + if (stream_index == RS_STREAM_DEPTH) + { + // set depth to color translation values in Projection matrix (P) + rs_extrinsics z_extrinsic; + rs_get_device_extrinsics (rs_device_, RS_STREAM_DEPTH, RS_STREAM_COLOR, &z_extrinsic, &rs_error_); check_error (); + camera_info_[stream_index]->P.at(3) = z_extrinsic.translation[0]/1000; // Tx + camera_info_[stream_index]->P.at(7) = z_extrinsic.translation[1]/1000; // Ty + camera_info_[stream_index]->P.at(11) = z_extrinsic.translation[2]/1000; // Tz + } + camera_info_[stream_index]->distortion_model = "plumb_bob"; // set R (rotation matrix) values to identity matrix From 2e34d3b4796dc0c2a4be7ce71b8d2c10ec00ab03 Mon Sep 17 00:00:00 2001 From: rjingar Date: Fri, 4 Mar 2016 16:16:34 -0800 Subject: [PATCH 057/124] Add dynamically enable/disable depth stream code --- camera/cfg/camera_params.cfg | 1 + camera/src/realsense_camera_nodelet.cpp | 277 ++++++++++++++++-------- camera/src/realsense_camera_nodelet.h | 4 + 3 files changed, 189 insertions(+), 93 deletions(-) diff --git a/camera/cfg/camera_params.cfg b/camera/cfg/camera_params.cfg index ce1d2376f7..9d60718b21 100755 --- a/camera/cfg/camera_params.cfg +++ b/camera/cfg/camera_params.cfg @@ -7,6 +7,7 @@ from dynamic_reconfigure.parameter_generator_catkin import * gen = ParameterGenerator() # Name Type Level Description Default Min Max +gen.add("ENABLE_DEPTH", bool_t, 0, "Enable Depth", True) gen.add("COLOR_BACKLIGHT_COMPENSATION", int_t, 0, "Backlight Compensation", 1, 0, 4) gen.add("COLOR_BRIGHTNESS", int_t, 0, "Brightness", 56, 0, 255) gen.add("COLOR_CONTRAST", int_t, 0, "Contrast", 32, 16, 64) diff --git a/camera/src/realsense_camera_nodelet.cpp b/camera/src/realsense_camera_nodelet.cpp index 361163cdac..cd475861ce 100644 --- a/camera/src/realsense_camera_nodelet.cpp +++ b/camera/src/realsense_camera_nodelet.cpp @@ -92,6 +92,9 @@ namespace realsense_camera frame_id_[RS_STREAM_INFRARED] = IR1_DEF_FRAME; frame_id_[RS_STREAM_INFRARED2] = IR2_DEF_FRAME; + for (int i = 0; i < STREAM_COUNT; ++i) + camera_info_[i] = NULL; + ros::NodeHandle & nh = getNodeHandle (); // Set up the topics. @@ -101,28 +104,18 @@ namespace realsense_camera getConfigValues (camera_configuration_); // Advertise the various topics and services. + // Advertise color stream only if color parameter is set. + camera_publisher_[RS_STREAM_COLOR] = it.advertiseCamera (COLOR_TOPIC, 1); // Advertise depth and infrared streams only if depth parameter is set. - if (enable_depth_ == true) + camera_publisher_[RS_STREAM_DEPTH] = it.advertiseCamera (DEPTH_TOPIC, 1); + camera_publisher_[RS_STREAM_INFRARED] = it.advertiseCamera (IR1_TOPIC, 1); + if (camera_.find (R200) != std::string::npos) { - camera_publisher_[RS_STREAM_DEPTH] = it.advertiseCamera (DEPTH_TOPIC, 1); - camera_publisher_[RS_STREAM_INFRARED] = it.advertiseCamera (IR1_TOPIC, 1); - if (camera_.find (R200) != std::string::npos) - { - camera_publisher_[RS_STREAM_INFRARED2] = it.advertiseCamera (IR2_TOPIC, 1); - } - - // Advertise pointcloud only if pointcloud parameter is set. - if (enable_pointcloud_ == true) - { - pointcloud_publisher_ = nh.advertise < sensor_msgs::PointCloud2 > (PC_TOPIC, 1); - } + camera_publisher_[RS_STREAM_INFRARED2] = it.advertiseCamera (IR2_TOPIC, 1); } - // Advertise color stream only if color parameter is set. - if (enable_color_ == true) - { - camera_publisher_[RS_STREAM_COLOR] = it.advertiseCamera (COLOR_TOPIC, 1); - } + pointcloud_publisher_ = nh.advertise < sensor_msgs::PointCloud2 > (PC_TOPIC, 1); + get_options_service_ = nh.advertiseService (SETTINGS_SERVICE, &RealsenseNodelet::getCameraSettings, this); @@ -156,6 +149,90 @@ namespace realsense_camera /* *Private Methods. */ + void RealsenseNodelet::enable_color_stream() + { + // Enable streams. + if (mode_.compare ("manual") == 0) + { + ROS_INFO_STREAM ("RealSense Camera - Enabling Color Stream: manual mode"); + rs_enable_stream (rs_device_, RS_STREAM_COLOR, color_width_, color_height_, COLOR_FORMAT, color_fps_, &rs_error_); + check_error (); + } + else + { + ROS_INFO_STREAM ("RealSense Camera - Enabling Color Stream: preset mode"); + rs_enable_stream_preset (rs_device_, RS_STREAM_COLOR, RS_PRESET_BEST_QUALITY, &rs_error_); check_error (); + } + + uint32_t stream_index = (uint32_t) RS_STREAM_COLOR; + if(camera_info_[stream_index] == NULL) { + prepareStreamCalibData (RS_STREAM_COLOR); + } + } + + void RealsenseNodelet::enable_depth_stream() + { + // Enable streams. + if (mode_.compare ("manual") == 0) + { + ROS_INFO_STREAM ("RealSense Camera - Enabling Depth Stream: manual mode"); + rs_enable_stream (rs_device_, RS_STREAM_DEPTH, depth_width_, depth_height_, DEPTH_FORMAT, depth_fps_, &rs_error_); + check_error (); + } + else + { + ROS_INFO_STREAM ("RealSense Camera - Enabling Depth Stream: preset mode"); + rs_enable_stream_preset (rs_device_, RS_STREAM_DEPTH, RS_PRESET_BEST_QUALITY, &rs_error_); check_error (); + } + + uint32_t stream_index = (uint32_t) RS_STREAM_DEPTH; + if(camera_info_[stream_index] == NULL) { + prepareStreamCalibData (RS_STREAM_DEPTH); + } + } + + void RealsenseNodelet::enable_infrared_stream() + { + // Enable streams. + if (mode_.compare ("manual") == 0) + { + ROS_INFO_STREAM ("RealSense Camera - Enabling Infrared Stream: manual mode"); + rs_enable_stream (rs_device_, RS_STREAM_INFRARED, depth_width_, depth_height_, IR1_FORMAT, depth_fps_, &rs_error_); + check_error (); + } + else + { + ROS_INFO_STREAM ("RealSense Camera - Enabling Infrared Stream: preset mode"); + rs_enable_stream_preset (rs_device_, RS_STREAM_INFRARED, RS_PRESET_BEST_QUALITY, &rs_error_); check_error (); + } + + uint32_t stream_index = (uint32_t) RS_STREAM_INFRARED; + if(camera_info_[stream_index] == NULL) { + prepareStreamCalibData (RS_STREAM_INFRARED); + } + } + + void RealsenseNodelet::enable_infrared2_stream() + { + // Enable streams. + if (mode_.compare ("manual") == 0) + { + ROS_INFO_STREAM ("RealSense Camera - Enabling Infrared2 Stream: manual mode"); + rs_enable_stream (rs_device_, RS_STREAM_INFRARED2, depth_width_, depth_height_, IR2_FORMAT, depth_fps_, 0); + } + else + { + ROS_INFO_STREAM ("RealSense Camera - Enabling Infrared2 Stream: preset mode"); + rs_enable_stream_preset (rs_device_, RS_STREAM_INFRARED2, RS_PRESET_BEST_QUALITY, 0); + } + uint32_t stream_index = (uint32_t) RS_STREAM_INFRARED2; + if(camera_info_[stream_index] == NULL) { + prepareStreamCalibData (RS_STREAM_INFRARED2); + } + } + + + void RealsenseNodelet::configCallback(realsense_camera::camera_paramsConfig &config, uint32_t level) { rs_set_device_option(rs_device_, RS_OPTION_COLOR_BACKLIGHT_COMPENSATION, config.COLOR_BACKLIGHT_COMPENSATION, 0); @@ -203,7 +280,15 @@ namespace realsense_camera edge_values_[3] = config.R200_AUTO_EXPOSURE_BOTTOM_EDGE; rs_set_device_options(rs_device_, edge_options_, 4, edge_values_, 0); - } + } + + if(config.ENABLE_DEPTH == false) { + enable_depth_ = false; + } + else { + enable_depth_ = true; + } + } void RealsenseNodelet::check_error () @@ -254,7 +339,7 @@ namespace realsense_camera ROS_INFO_STREAM ("RealSense Camera - Number of cameras connected: " << num_of_cameras); ROS_INFO_STREAM ("RealSense Camera - Firmware version: " << - rs_get_device_firmware_version (rs_device_, &rs_error_)); + rs_get_device_firmware_version (rs_device_, &rs_error_)); check_error (); ROS_INFO_STREAM ("RealSense Camera - Name: " << rs_get_device_name (rs_device_, &rs_error_)); check_error (); @@ -262,36 +347,16 @@ namespace realsense_camera check_error (); // Enable streams. - if (enable_depth_ == true) + if (enable_color_ == true) { - if (mode_.compare ("manual") == 0) - { - ROS_INFO_STREAM ("RealSense Camera - Enabling Depth Stream: manual mode"); - rs_enable_stream (rs_device_, RS_STREAM_DEPTH, depth_width_, depth_height_, DEPTH_FORMAT, depth_fps_, &rs_error_); - rs_enable_stream (rs_device_, RS_STREAM_INFRARED, depth_width_, depth_height_, IR1_FORMAT, depth_fps_, &rs_error_); - rs_enable_stream (rs_device_, RS_STREAM_INFRARED2, depth_width_, depth_height_, IR2_FORMAT, depth_fps_, 0); - } - else - { - ROS_INFO_STREAM ("RealSense Camera - Enabling Depth Stream: preset mode"); - rs_enable_stream_preset (rs_device_, RS_STREAM_DEPTH, RS_PRESET_BEST_QUALITY, &rs_error_); check_error (); - rs_enable_stream_preset (rs_device_, RS_STREAM_INFRARED, RS_PRESET_BEST_QUALITY, &rs_error_); check_error (); - rs_enable_stream_preset (rs_device_, RS_STREAM_INFRARED2, RS_PRESET_BEST_QUALITY, 0); - } + enable_color_stream(); } - if (enable_color_ == true) + if (enable_depth_ == true) { - if (mode_.compare ("manual") == 0) - { - ROS_INFO_STREAM ("RealSense Camera - Enabling Color Stream: manual mode"); - rs_enable_stream (rs_device_, RS_STREAM_COLOR, color_width_, color_height_, COLOR_FORMAT, color_fps_, &rs_error_); - } - else - { - ROS_INFO_STREAM ("RealSense Camera - Enabling Color Stream: preset mode"); - rs_enable_stream_preset (rs_device_, RS_STREAM_COLOR, RS_PRESET_BEST_QUALITY, &rs_error_); check_error (); - } + enable_depth_stream(); + enable_infrared_stream(); + enable_infrared2_stream(); } for (int i = 0; i < RS_OPTION_COUNT; ++i) @@ -299,7 +364,7 @@ namespace realsense_camera option_str o = { (rs_option) i}; - if (!rs_device_supports_option (rs_device_, o.opt, &rs_error_)) + if (!rs_device_supports_option (rs_device_, o.opt, 0)) { continue; } @@ -318,6 +383,7 @@ namespace realsense_camera // Start device. rs_start_device (rs_device_, &rs_error_); + check_error (); is_device_started_ = true; @@ -334,26 +400,12 @@ namespace realsense_camera // Prepare camera for enabled streams (color/depth/infrared/infrared2). fillStreamEncoding (); - if (rs_is_stream_enabled (rs_device_, RS_STREAM_COLOR, 0)) - { - image_[(uint32_t) RS_STREAM_COLOR] = cv::Mat (color_height_, color_width_, CV_8UC3, cv::Scalar (0, 0, 0)); - prepareStreamCalibData (RS_STREAM_COLOR); - } - - if (rs_is_stream_enabled (rs_device_, RS_STREAM_DEPTH, 0)) + image_[(uint32_t) RS_STREAM_COLOR] = cv::Mat (color_height_, color_width_, CV_8UC3, cv::Scalar (0, 0, 0)); + image_[(uint32_t) RS_STREAM_DEPTH] = cv::Mat (depth_height_, depth_width_, CV_16UC1, cv::Scalar (0)); + image_[(uint32_t) RS_STREAM_INFRARED] = cv::Mat (depth_height_, depth_width_, CV_8UC1, cv::Scalar (0)); + if (camera_.find (R200) != std::string::npos) { - // Define message. - image_[(uint32_t) RS_STREAM_DEPTH] = cv::Mat (depth_height_, depth_width_, CV_16UC1, cv::Scalar (0)); - prepareStreamCalibData (RS_STREAM_DEPTH); - - image_[(uint32_t) RS_STREAM_INFRARED] = cv::Mat (depth_height_, depth_width_, CV_8UC1, cv::Scalar (0)); - prepareStreamCalibData (RS_STREAM_INFRARED); - - if (rs_is_stream_enabled (rs_device_, RS_STREAM_INFRARED2, 0)) - { image_[(uint32_t) RS_STREAM_INFRARED2] = cv::Mat (depth_height_, depth_width_, CV_8UC1, cv::Scalar (0)); - prepareStreamCalibData (RS_STREAM_INFRARED2); - } } } @@ -425,7 +477,7 @@ namespace realsense_camera { option_str o = { (rs_option) i}; - if (!rs_device_supports_option (rs_device_, o.opt, &rs_error_)) + if (!rs_device_supports_option (rs_device_, o.opt, 0)) { continue; } @@ -636,45 +688,84 @@ namespace realsense_camera */ void RealsenseNodelet::publishStreams () { - rs_wait_for_frames (rs_device_, &rs_error_); - check_error (); - time_stamp_ = ros::Time::now (); - - for (int stream_index = 0; stream_index < STREAM_COUNT; ++stream_index) + if(enable_depth_ == false && rs_is_stream_enabled (rs_device_, RS_STREAM_DEPTH, 0) == 1) { - // Publish image stream only if there is at least one subscriber. - if (camera_publisher_[stream_index].getNumSubscribers () > 0) + if(rs_is_device_streaming(rs_device_, 0) == 1) { - prepareStreamData ((rs_stream) stream_index); - - sensor_msgs::ImagePtr msg = cv_bridge::CvImage (std_msgs::Header (), - stream_encoding_[stream_index], - image_[stream_index]).toImageMsg (); + rs_stop_device (rs_device_, &rs_error_); check_error (); + ROS_INFO_STREAM ("RealSense Camera - Device Stopped"); + } - msg->header.frame_id = frame_id_[stream_index]; - msg->header.stamp = time_stamp_; // Publish timestamp to synchronize frames. - msg->width = image_[stream_index].cols; - msg->height = image_[stream_index].rows; - msg->is_bigendian = false; - msg->step = stream_step_[stream_index]; + rs_disable_stream(rs_device_, RS_STREAM_DEPTH, &rs_error_); check_error (); + ROS_INFO_STREAM ("RealSense Camera - Depth Stream Disabled"); - camera_info_ptr_[stream_index]->header.stamp = msg->header.stamp; - camera_publisher_[stream_index].publish (msg, camera_info_ptr_[stream_index]); + if(rs_is_device_streaming(rs_device_, 0) == 0) + { + rs_start_device (rs_device_, &rs_error_);check_error (); + ROS_INFO_STREAM ("RealSense Camera - Device Started"); + } + } + + if(enable_depth_ == true && rs_is_stream_enabled (rs_device_, RS_STREAM_DEPTH, 0) == 0) + { + if(rs_is_device_streaming(rs_device_, 0) == 1) + { + rs_stop_device (rs_device_, &rs_error_); check_error (); + ROS_INFO_STREAM ("RealSense Camera - Device Stopped"); + } + + enable_depth_stream(); + + if(rs_is_device_streaming(rs_device_, 0) == 0) + { + rs_start_device (rs_device_, &rs_error_); check_error (); + ROS_INFO_STREAM ("RealSense Camera - Device Started"); } } - if (pointcloud_publisher_.getNumSubscribers () > 0 && rs_is_stream_enabled (rs_device_, RS_STREAM_DEPTH, 0) - && enable_pointcloud_ == true) + if(rs_is_device_streaming(rs_device_, 0) == 1) { - if (camera_publisher_[(uint32_t) RS_STREAM_DEPTH].getNumSubscribers () <= 0) + rs_wait_for_frames (rs_device_, &rs_error_); + check_error (); + time_stamp_ = ros::Time::now (); + + for (int stream_index = 0; stream_index < STREAM_COUNT; ++stream_index) { - prepareStreamData (RS_STREAM_DEPTH); + // Publish image stream only if there is at least one subscriber. + if (camera_publisher_[stream_index].getNumSubscribers () > 0 && + rs_is_stream_enabled (rs_device_, (rs_stream) stream_index, 0) == 1) + { + prepareStreamData ((rs_stream) stream_index); + + sensor_msgs::ImagePtr msg = cv_bridge::CvImage (std_msgs::Header (), + stream_encoding_[stream_index], + image_[stream_index]).toImageMsg (); + + msg->header.frame_id = frame_id_[stream_index]; + msg->header.stamp = time_stamp_; // Publish timestamp to synchronize frames. + msg->width = image_[stream_index].cols; + msg->height = image_[stream_index].rows; + msg->is_bigendian = false; + msg->step = stream_step_[stream_index]; + + camera_info_ptr_[stream_index]->header.stamp = msg->header.stamp; + camera_publisher_[stream_index].publish (msg, camera_info_ptr_[stream_index]); + } } - if (camera_publisher_[(uint32_t) RS_STREAM_COLOR].getNumSubscribers () <= 0) + + if (pointcloud_publisher_.getNumSubscribers () > 0 && rs_is_stream_enabled (rs_device_, RS_STREAM_DEPTH, 0) == 1 + && enable_pointcloud_ == true) { - prepareStreamData (RS_STREAM_COLOR); + if (camera_publisher_[(uint32_t) RS_STREAM_DEPTH].getNumSubscribers () <= 0) + { + prepareStreamData (RS_STREAM_DEPTH); + } + if (camera_publisher_[(uint32_t) RS_STREAM_COLOR].getNumSubscribers () <= 0) + { + prepareStreamData (RS_STREAM_COLOR); + } + publishPointCloud (image_[(uint32_t) RS_STREAM_COLOR]); } - publishPointCloud (image_[(uint32_t) RS_STREAM_COLOR]); } } diff --git a/camera/src/realsense_camera_nodelet.h b/camera/src/realsense_camera_nodelet.h index dd27b3f8a1..645c2433e0 100644 --- a/camera/src/realsense_camera_nodelet.h +++ b/camera/src/realsense_camera_nodelet.h @@ -165,6 +165,10 @@ class RealsenseNodelet: public nodelet::Nodelet boost::shared_ptr> dynamic_reconf_server_; // Member Functions. + void enable_color_stream(); + void enable_depth_stream(); + void enable_infrared_stream(); + void enable_infrared2_stream(); void check_error(); void fetchCalibData(); void prepareStreamCalibData(rs_stream calib_data); From dc9881ac425d5996d37376f50cc7bc33bbc5fde8 Mon Sep 17 00:00:00 2001 From: rjingar Date: Thu, 10 Mar 2016 17:53:40 -0800 Subject: [PATCH 058/124] Add unit tests for Enable/disable depth stream --- camera/test/realsense_camera_test_node.cpp | 24 ++++++++++++++++------ camera/test/realsense_camera_test_node.h | 2 ++ 2 files changed, 20 insertions(+), 6 deletions(-) diff --git a/camera/test/realsense_camera_test_node.cpp b/camera/test/realsense_camera_test_node.cpp index 7cfccd9e01..1daeb29b0b 100644 --- a/camera/test/realsense_camera_test_node.cpp +++ b/camera/test/realsense_camera_test_node.cpp @@ -262,6 +262,18 @@ TEST (RealsenseTests, testColorCameraInfo) } } +TEST (RealsenseTests, testIsDepthStreamEnabled) +{ + if (enable_depth) + { + EXPECT_TRUE (depth_recv); + } + else + { + EXPECT_FALSE (depth_recv); + } +} + TEST (RealsenseTests, testDepthStream) { if (enable_depth) @@ -317,7 +329,7 @@ TEST (RealsenseTests, testDepthCameraInfo) TEST (RealsenseTests, testInfrared1Stream) { - if (enable_depth) + if (enable_infrared1) { EXPECT_TRUE (infrared1_avg > 0); EXPECT_TRUE (infrared1_recv); @@ -338,7 +350,7 @@ TEST (RealsenseTests, testInfrared1Stream) TEST (RealsenseTests, testInfrared1Resolution) { - if (enable_depth) + if (enable_infrared1) { if (depth_width_exp > 0) { @@ -353,7 +365,7 @@ TEST (RealsenseTests, testInfrared1Resolution) TEST (RealsenseTests, testInfrared1CameraInfo) { - if (enable_depth) + if (enable_infrared1) { EXPECT_EQ (infrared1_width_recv, inf1_caminfo_width_recv); EXPECT_EQ (infrared1_height_recv, inf1_caminfo_height_recv); @@ -369,7 +381,7 @@ TEST (RealsenseTests, testInfrared1CameraInfo) TEST (RealsenseTests, testInfrared2Stream) { - if (enable_depth) + if (enable_infrared2) { EXPECT_TRUE (infrared2_avg > 0); EXPECT_TRUE (infrared2_recv); @@ -382,7 +394,7 @@ TEST (RealsenseTests, testInfrared2Stream) TEST (RealsenseTests, testInfrared2Resolution) { - if (enable_depth) + if (enable_infrared2) { if (depth_width_exp > 0) { @@ -397,7 +409,7 @@ TEST (RealsenseTests, testInfrared2Resolution) TEST (RealsenseTests, testInfrared2CameraInfo) { - if (enable_depth) + if (enable_infrared2) { EXPECT_EQ (infrared2_width_recv, inf2_caminfo_width_recv); EXPECT_EQ (infrared2_height_recv, inf2_caminfo_height_recv); diff --git a/camera/test/realsense_camera_test_node.h b/camera/test/realsense_camera_test_node.h index 5e9dc5c6aa..ab06dbe8fc 100644 --- a/camera/test/realsense_camera_test_node.h +++ b/camera/test/realsense_camera_test_node.h @@ -80,6 +80,8 @@ uint32_t infrared2_step_exp; // Expected infrared2 step. bool enable_color = true; bool enable_depth = true; +bool enable_infrared1 = true; +bool enable_infrared2 = true; bool enable_pointcloud = true; std::string depth_encoding_exp; // Expected depth encoding. From 2ad69beb105d9583c45c92478edbaa7dc03bee95 Mon Sep 17 00:00:00 2001 From: Matthew Hansen Date: Fri, 11 Mar 2016 15:54:33 -0800 Subject: [PATCH 059/124] Add tests for depth translation to color --- camera/test/realsense_camera_test_node.cpp | 83 ++++++++++++++++++++++ camera/test/realsense_camera_test_node.h | 5 ++ 2 files changed, 88 insertions(+) diff --git a/camera/test/realsense_camera_test_node.cpp b/camera/test/realsense_camera_test_node.cpp index 7cfccd9e01..2515ab1bee 100644 --- a/camera/test/realsense_camera_test_node.cpp +++ b/camera/test/realsense_camera_test_node.cpp @@ -66,6 +66,12 @@ void imageInfrared1Callback(const sensor_msgs::ImageConstPtr & msg, const sensor inf1_caminfo_rotation_recv[i] = info_msg->R[i]; } + // copy projection matrix + for (unsigned int i = 0; i < sizeof(info_msg->P)/sizeof(double); i++) + { + inf1_caminfo_projection_recv[i] = info_msg->P[i]; + } + infrared1_recv = true; } @@ -103,6 +109,12 @@ void imageInfrared2Callback(const sensor_msgs::ImageConstPtr & msg, const sensor inf2_caminfo_rotation_recv[i] = info_msg->R[i]; } + // copy projection matrix + for (unsigned int i = 0; i < sizeof(info_msg->P)/sizeof(double); i++) + { + inf2_caminfo_projection_recv[i] = info_msg->P[i]; + } + infrared2_recv = true; } @@ -141,6 +153,11 @@ void imageDepthCallback(const sensor_msgs::ImageConstPtr & msg, const sensor_msg { depth_caminfo_rotation_recv[i] = info_msg->R[i]; } + // copy projection matrix + for (unsigned int i = 0; i < sizeof(info_msg->P)/sizeof(double); i++) + { + depth_caminfo_projection_recv[i] = info_msg->P[i]; + } depth_recv = true; } @@ -206,6 +223,12 @@ void imageColorCallback(const sensor_msgs::ImageConstPtr & msg, const sensor_msg color_caminfo_rotation_recv[i] = info_msg->R[i]; } + // copy projection matrix + for (unsigned int i = 0; i < sizeof(info_msg->P)/sizeof(double); i++) + { + color_caminfo_projection_recv[i] = info_msg->P[i]; + } + color_recv = true; } @@ -259,6 +282,21 @@ TEST (RealsenseTests, testColorCameraInfo) { EXPECT_EQ (ROTATION_IDENTITY[i], color_caminfo_rotation_recv[i]); } + + // check projection matrix values are set + EXPECT_TRUE(color_caminfo_projection_recv[0] != (double) 0); + EXPECT_EQ(color_caminfo_projection_recv[1], (double) 0); + EXPECT_TRUE(color_caminfo_projection_recv[2] != (double) 0); + EXPECT_EQ(color_caminfo_projection_recv[3], (double) 0); + EXPECT_EQ(color_caminfo_projection_recv[4], (double) 0); + EXPECT_TRUE(color_caminfo_projection_recv[5] != (double) 0); + EXPECT_TRUE(color_caminfo_projection_recv[6] != (double) 0); + EXPECT_EQ(color_caminfo_projection_recv[7], (double) 0); + EXPECT_EQ(color_caminfo_projection_recv[8], (double) 0); + EXPECT_EQ(color_caminfo_projection_recv[9], (double) 0); + EXPECT_TRUE(color_caminfo_projection_recv[10] != (double) 0); + EXPECT_EQ(color_caminfo_projection_recv[11], (double) 0); + } } @@ -312,6 +350,21 @@ TEST (RealsenseTests, testDepthCameraInfo) { EXPECT_EQ (ROTATION_IDENTITY[i], depth_caminfo_rotation_recv[i]); } + + // check projection matrix values are set + EXPECT_TRUE(depth_caminfo_projection_recv[0] != (double) 0); + EXPECT_EQ(depth_caminfo_projection_recv[1], (double) 0); + EXPECT_TRUE(depth_caminfo_projection_recv[2] != (double) 0); + EXPECT_TRUE(depth_caminfo_projection_recv[3] != (double) 0); + EXPECT_EQ(depth_caminfo_projection_recv[4], (double) 0); + EXPECT_TRUE(depth_caminfo_projection_recv[5] != (double) 0); + EXPECT_TRUE(depth_caminfo_projection_recv[6] != (double) 0); + EXPECT_TRUE(depth_caminfo_projection_recv[7] != (double) 0); + EXPECT_EQ(depth_caminfo_projection_recv[8], (double) 0); + EXPECT_EQ(depth_caminfo_projection_recv[9], (double) 0); + EXPECT_TRUE(depth_caminfo_projection_recv[10] != (double) 0); + EXPECT_TRUE(depth_caminfo_projection_recv[11] != (double) 0); + } } @@ -364,6 +417,21 @@ TEST (RealsenseTests, testInfrared1CameraInfo) { EXPECT_EQ (ROTATION_IDENTITY[i], inf1_caminfo_rotation_recv[i]); } + + // check projection matrix values are set + EXPECT_TRUE(inf1_caminfo_projection_recv[0] != (double) 0); + EXPECT_EQ(inf1_caminfo_projection_recv[1], (double) 0); + EXPECT_TRUE(inf1_caminfo_projection_recv[2] != (double) 0); + EXPECT_EQ(inf1_caminfo_projection_recv[3], (double) 0); + EXPECT_EQ(inf1_caminfo_projection_recv[4], (double) 0); + EXPECT_TRUE(inf1_caminfo_projection_recv[5] != (double) 0); + EXPECT_TRUE(inf1_caminfo_projection_recv[6] != (double) 0); + EXPECT_EQ(inf1_caminfo_projection_recv[7], (double) 0); + EXPECT_EQ(inf1_caminfo_projection_recv[8], (double) 0); + EXPECT_EQ(inf1_caminfo_projection_recv[9], (double) 0); + EXPECT_TRUE(inf1_caminfo_projection_recv[10] != (double) 0); + EXPECT_EQ(inf1_caminfo_projection_recv[11], (double) 0); + } } @@ -408,6 +476,21 @@ TEST (RealsenseTests, testInfrared2CameraInfo) { EXPECT_EQ (ROTATION_IDENTITY[i], inf2_caminfo_rotation_recv[i]); } + + // check projection matrix values are set + EXPECT_TRUE(inf2_caminfo_projection_recv[0] != (double) 0); + EXPECT_EQ(inf2_caminfo_projection_recv[1], (double) 0); + EXPECT_TRUE(inf2_caminfo_projection_recv[2] != (double) 0); + EXPECT_EQ(inf2_caminfo_projection_recv[3], (double) 0); + EXPECT_EQ(inf2_caminfo_projection_recv[4], (double) 0); + EXPECT_TRUE(inf2_caminfo_projection_recv[5] != (double) 0); + EXPECT_TRUE(inf2_caminfo_projection_recv[6] != (double) 0); + EXPECT_EQ(inf2_caminfo_projection_recv[7], (double) 0); + EXPECT_EQ(inf2_caminfo_projection_recv[8], (double) 0); + EXPECT_EQ(inf2_caminfo_projection_recv[9], (double) 0); + EXPECT_TRUE(inf2_caminfo_projection_recv[10] != (double) 0); + EXPECT_EQ(inf2_caminfo_projection_recv[11], (double) 0); + } } diff --git a/camera/test/realsense_camera_test_node.h b/camera/test/realsense_camera_test_node.h index 5e9dc5c6aa..df3cc4049a 100644 --- a/camera/test/realsense_camera_test_node.h +++ b/camera/test/realsense_camera_test_node.h @@ -123,18 +123,23 @@ std::string infrared1_encoding_recv; // Expected depth encoding. std::string infrared2_encoding_recv; // Expected depth encoding. std::string color_encoding_recv; // Expected color encoding. + int depth_caminfo_height_recv = 0; int depth_caminfo_width_recv = 0; double depth_caminfo_rotation_recv[9] = {0}; +double depth_caminfo_projection_recv[12] = {0}; int color_caminfo_height_recv = 0; int color_caminfo_width_recv = 0; double color_caminfo_rotation_recv[9] = {0}; +double color_caminfo_projection_recv[12] = {0}; int inf1_caminfo_height_recv = 0; int inf1_caminfo_width_recv = 0; double inf1_caminfo_rotation_recv[9] = {0}; +double inf1_caminfo_projection_recv[12] = {0}; int inf2_caminfo_height_recv = 0; int inf2_caminfo_width_recv = 0; double inf2_caminfo_rotation_recv[9] = {0}; +double inf2_caminfo_projection_recv[12] = {0}; std::string inf1_dmodel_recv; std::string inf2_dmodel_recv; From 7ff2eeba7f47000bce910ad0f6b51e1cc18c5795 Mon Sep 17 00:00:00 2001 From: rjingar Date: Mon, 14 Mar 2016 08:39:58 -0700 Subject: [PATCH 060/124] Added Enable/disable infrared streams along with depth stream --- camera/src/realsense_camera_nodelet.cpp | 10 +++++++++- 1 file changed, 9 insertions(+), 1 deletion(-) diff --git a/camera/src/realsense_camera_nodelet.cpp b/camera/src/realsense_camera_nodelet.cpp index cd475861ce..4b8847626f 100644 --- a/camera/src/realsense_camera_nodelet.cpp +++ b/camera/src/realsense_camera_nodelet.cpp @@ -699,6 +699,12 @@ namespace realsense_camera rs_disable_stream(rs_device_, RS_STREAM_DEPTH, &rs_error_); check_error (); ROS_INFO_STREAM ("RealSense Camera - Depth Stream Disabled"); + rs_disable_stream(rs_device_, RS_STREAM_INFRARED, &rs_error_); check_error (); + ROS_INFO_STREAM ("RealSense Camera - Infrared1 stream Disabled"); + + rs_disable_stream(rs_device_, RS_STREAM_INFRARED2, &rs_error_); check_error (); + ROS_INFO_STREAM ("RealSense Camera - Infrared2 stream Disabled"); + if(rs_is_device_streaming(rs_device_, 0) == 0) { rs_start_device (rs_device_, &rs_error_);check_error (); @@ -715,7 +721,9 @@ namespace realsense_camera } enable_depth_stream(); - + enable_infrared_stream(); + enable_infrared2_stream(); + if(rs_is_device_streaming(rs_device_, 0) == 0) { rs_start_device (rs_device_, &rs_error_); check_error (); From 589eeeaf9dfdb82bab6b37030feeecb2e37f9646 Mon Sep 17 00:00:00 2001 From: rjingar Date: Mon, 14 Mar 2016 14:58:42 -0700 Subject: [PATCH 061/124] Added Enable/disable infrared streams along with depth stream. --- camera/README.md | 7 +- camera/src/realsense_camera_nodelet.cpp | 109 ++++++++++++--------- camera/src/realsense_camera_nodelet.h | 10 +- camera/test/realsense_camera_test_node.cpp | 16 +-- 4 files changed, 83 insertions(+), 59 deletions(-) diff --git a/camera/README.md b/camera/README.md index 46959655a1..f804bfd891 100644 --- a/camera/README.md +++ b/camera/README.md @@ -88,7 +88,7 @@ Infrared2 camera depth_fps (int, default: 60) Specify the depth camera FPS enable_depth (bool, default: true) - Specify if to enable or not the depth camera. + Specify if to enable or not the depth and infrared camera. enable_color (bool, default: true) Specify if to enable or not the color camera. enable_pointcloud (bool, default: true) @@ -141,6 +141,11 @@ To get supported camera options with current value set. It returns string in opt R200_AUTO_EXPOSURE_LEFT_EDGE R200_AUTO_EXPOSURE_RIGHT_EDGE + Enable/Disable Stream: + ENABLE_DEPTH + Check or uncheck the option to disable/enable depth and infrared streams dynamically. + Note: Infrared streams will be enabled or disabled along with depth stream. + Use rqt_reconfigure GUI to view and edit the parameters that are accessible via dynamic_reconfigure. Command to launch GUI: diff --git a/camera/src/realsense_camera_nodelet.cpp b/camera/src/realsense_camera_nodelet.cpp index 4b8847626f..37fc057ed3 100644 --- a/camera/src/realsense_camera_nodelet.cpp +++ b/camera/src/realsense_camera_nodelet.cpp @@ -58,7 +58,7 @@ namespace realsense_camera { rs_stop_device (rs_device_, 0); rs_delete_context (rs_context_, &rs_error_); - check_error (); + checkError (); } ROS_INFO_STREAM ("RealSense Camera - Stopping camera nodelet."); @@ -149,19 +149,19 @@ namespace realsense_camera /* *Private Methods. */ - void RealsenseNodelet::enable_color_stream() + void RealsenseNodelet::enableColorStream() { // Enable streams. if (mode_.compare ("manual") == 0) { ROS_INFO_STREAM ("RealSense Camera - Enabling Color Stream: manual mode"); rs_enable_stream (rs_device_, RS_STREAM_COLOR, color_width_, color_height_, COLOR_FORMAT, color_fps_, &rs_error_); - check_error (); + checkError (); } else { ROS_INFO_STREAM ("RealSense Camera - Enabling Color Stream: preset mode"); - rs_enable_stream_preset (rs_device_, RS_STREAM_COLOR, RS_PRESET_BEST_QUALITY, &rs_error_); check_error (); + rs_enable_stream_preset (rs_device_, RS_STREAM_COLOR, RS_PRESET_BEST_QUALITY, &rs_error_); checkError (); } uint32_t stream_index = (uint32_t) RS_STREAM_COLOR; @@ -170,49 +170,51 @@ namespace realsense_camera } } - void RealsenseNodelet::enable_depth_stream() + void RealsenseNodelet::enableDepthStream() { // Enable streams. if (mode_.compare ("manual") == 0) { ROS_INFO_STREAM ("RealSense Camera - Enabling Depth Stream: manual mode"); rs_enable_stream (rs_device_, RS_STREAM_DEPTH, depth_width_, depth_height_, DEPTH_FORMAT, depth_fps_, &rs_error_); - check_error (); + checkError (); } else { ROS_INFO_STREAM ("RealSense Camera - Enabling Depth Stream: preset mode"); - rs_enable_stream_preset (rs_device_, RS_STREAM_DEPTH, RS_PRESET_BEST_QUALITY, &rs_error_); check_error (); + rs_enable_stream_preset (rs_device_, RS_STREAM_DEPTH, RS_PRESET_BEST_QUALITY, &rs_error_); checkError (); } uint32_t stream_index = (uint32_t) RS_STREAM_DEPTH; - if(camera_info_[stream_index] == NULL) { + if(camera_info_[stream_index] == NULL) + { prepareStreamCalibData (RS_STREAM_DEPTH); } } - void RealsenseNodelet::enable_infrared_stream() + void RealsenseNodelet::enableInfraredStream() { // Enable streams. if (mode_.compare ("manual") == 0) { ROS_INFO_STREAM ("RealSense Camera - Enabling Infrared Stream: manual mode"); rs_enable_stream (rs_device_, RS_STREAM_INFRARED, depth_width_, depth_height_, IR1_FORMAT, depth_fps_, &rs_error_); - check_error (); + checkError (); } else { ROS_INFO_STREAM ("RealSense Camera - Enabling Infrared Stream: preset mode"); - rs_enable_stream_preset (rs_device_, RS_STREAM_INFRARED, RS_PRESET_BEST_QUALITY, &rs_error_); check_error (); + rs_enable_stream_preset (rs_device_, RS_STREAM_INFRARED, RS_PRESET_BEST_QUALITY, &rs_error_); checkError (); } uint32_t stream_index = (uint32_t) RS_STREAM_INFRARED; - if(camera_info_[stream_index] == NULL) { + if(camera_info_[stream_index] == NULL) + { prepareStreamCalibData (RS_STREAM_INFRARED); } } - void RealsenseNodelet::enable_infrared2_stream() + void RealsenseNodelet::enableInfrared2Stream() { // Enable streams. if (mode_.compare ("manual") == 0) @@ -225,8 +227,10 @@ namespace realsense_camera ROS_INFO_STREAM ("RealSense Camera - Enabling Infrared2 Stream: preset mode"); rs_enable_stream_preset (rs_device_, RS_STREAM_INFRARED2, RS_PRESET_BEST_QUALITY, 0); } + uint32_t stream_index = (uint32_t) RS_STREAM_INFRARED2; - if(camera_info_[stream_index] == NULL) { + if(camera_info_[stream_index] == NULL) + { prepareStreamCalibData (RS_STREAM_INFRARED2); } } @@ -282,16 +286,25 @@ namespace realsense_camera rs_set_device_options(rs_device_, edge_options_, 4, edge_values_, 0); } - if(config.ENABLE_DEPTH == false) { - enable_depth_ = false; + if(config.ENABLE_DEPTH == false) + { + if(enable_color_ == false) + { + ROS_INFO_STREAM ("RealSense Camera - Color stream is also disabled. Cannot disable depth stream"); + config.ENABLE_DEPTH = true; + } + else + { + enable_depth_ = false; + } } - else { + else + { enable_depth_ = true; } - } - void RealsenseNodelet::check_error () + void RealsenseNodelet::checkError () { if (rs_error_) { @@ -325,7 +338,7 @@ namespace realsense_camera } rs_context_ = rs_create_context (RS_API_VERSION, &rs_error_); - check_error (); + checkError (); int num_of_cameras = rs_get_device_count (rs_context_, NULL); if (num_of_cameras < 1) @@ -335,28 +348,28 @@ namespace realsense_camera } rs_device_ = rs_get_device (rs_context_, 0, &rs_error_); - check_error (); + checkError (); ROS_INFO_STREAM ("RealSense Camera - Number of cameras connected: " << num_of_cameras); ROS_INFO_STREAM ("RealSense Camera - Firmware version: " << rs_get_device_firmware_version (rs_device_, &rs_error_)); - check_error (); + checkError (); ROS_INFO_STREAM ("RealSense Camera - Name: " << rs_get_device_name (rs_device_, &rs_error_)); - check_error (); + checkError (); ROS_INFO_STREAM ("RealSense Camera - Serial no: " << rs_get_device_serial (rs_device_, &rs_error_)); - check_error (); + checkError (); // Enable streams. if (enable_color_ == true) { - enable_color_stream(); + enableColorStream(); } if (enable_depth_ == true) { - enable_depth_stream(); - enable_infrared_stream(); - enable_infrared2_stream(); + enableDepthStream(); + enableInfraredStream(); + enableInfrared2Stream(); } for (int i = 0; i < RS_OPTION_COUNT; ++i) @@ -383,7 +396,7 @@ namespace realsense_camera // Start device. rs_start_device (rs_device_, &rs_error_); - check_error (); + checkError (); is_device_started_ = true; @@ -417,7 +430,7 @@ namespace realsense_camera uint32_t stream_index = (uint32_t) rs_strm; rs_intrinsics intrinsic; rs_get_stream_intrinsics (rs_device_, rs_strm, &intrinsic, &rs_error_); - check_error (); + checkError (); camera_info_[stream_index] = new sensor_msgs::CameraInfo (); camera_info_ptr_[stream_index] = sensor_msgs::CameraInfoPtr (camera_info_[stream_index]); @@ -634,7 +647,7 @@ namespace realsense_camera { ROS_INFO_STREAM ("RealSense Camera - Setting" << opt_name.c_str () << " to " << config_.at (opt_name).c_str ()); rs_set_device_option (rs_device_, o.opt, atoi (config_.at (opt_name).c_str ()), &rs_error_); - check_error (); + checkError (); } cam_options.pop_back (); } @@ -692,22 +705,24 @@ namespace realsense_camera { if(rs_is_device_streaming(rs_device_, 0) == 1) { - rs_stop_device (rs_device_, &rs_error_); check_error (); + rs_stop_device (rs_device_, &rs_error_); checkError (); ROS_INFO_STREAM ("RealSense Camera - Device Stopped"); } - rs_disable_stream(rs_device_, RS_STREAM_DEPTH, &rs_error_); check_error (); + + //disable depth, infrared1 and infrared2 streams + rs_disable_stream(rs_device_, RS_STREAM_DEPTH, &rs_error_); checkError (); ROS_INFO_STREAM ("RealSense Camera - Depth Stream Disabled"); - rs_disable_stream(rs_device_, RS_STREAM_INFRARED, &rs_error_); check_error (); + rs_disable_stream(rs_device_, RS_STREAM_INFRARED, &rs_error_); checkError (); ROS_INFO_STREAM ("RealSense Camera - Infrared1 stream Disabled"); - rs_disable_stream(rs_device_, RS_STREAM_INFRARED2, &rs_error_); check_error (); + rs_disable_stream(rs_device_, RS_STREAM_INFRARED2, &rs_error_); checkError (); ROS_INFO_STREAM ("RealSense Camera - Infrared2 stream Disabled"); if(rs_is_device_streaming(rs_device_, 0) == 0) { - rs_start_device (rs_device_, &rs_error_);check_error (); + rs_start_device (rs_device_, &rs_error_);checkError (); ROS_INFO_STREAM ("RealSense Camera - Device Started"); } } @@ -716,17 +731,17 @@ namespace realsense_camera { if(rs_is_device_streaming(rs_device_, 0) == 1) { - rs_stop_device (rs_device_, &rs_error_); check_error (); + rs_stop_device (rs_device_, &rs_error_); checkError (); ROS_INFO_STREAM ("RealSense Camera - Device Stopped"); } - enable_depth_stream(); - enable_infrared_stream(); - enable_infrared2_stream(); + enableDepthStream(); + enableInfraredStream(); + enableInfrared2Stream(); if(rs_is_device_streaming(rs_device_, 0) == 0) { - rs_start_device (rs_device_, &rs_error_); check_error (); + rs_start_device (rs_device_, &rs_error_); checkError (); ROS_INFO_STREAM ("RealSense Camera - Device Started"); } } @@ -734,7 +749,7 @@ namespace realsense_camera if(rs_is_device_streaming(rs_device_, 0) == 1) { rs_wait_for_frames (rs_device_, &rs_error_); - check_error (); + checkError (); time_stamp_ = ros::Time::now (); for (int stream_index = 0; stream_index < STREAM_COUNT; ++stream_index) @@ -790,12 +805,12 @@ namespace realsense_camera rs_intrinsics z_intrinsic; rs_get_stream_intrinsics (rs_device_, RS_STREAM_DEPTH, &z_intrinsic, &rs_error_); - check_error (); + checkError (); if (enable_color_ == true) { - rs_get_stream_intrinsics (rs_device_, RS_STREAM_COLOR, &color_intrinsic, &rs_error_); check_error (); - rs_get_device_extrinsics (rs_device_, RS_STREAM_DEPTH, RS_STREAM_COLOR, &z_extrinsic, &rs_error_); check_error (); + rs_get_stream_intrinsics (rs_device_, RS_STREAM_COLOR, &color_intrinsic, &rs_error_); checkError (); + rs_get_device_extrinsics (rs_device_, RS_STREAM_DEPTH, RS_STREAM_COLOR, &z_extrinsic, &rs_error_); checkError (); } // Convert pointcloud from the camera to pointcloud object for ROS. @@ -826,7 +841,7 @@ namespace realsense_camera float depth_point[3], color_point[3], color_pixel[2], scaled_depth; unsigned char *color_data = image_color.data; const float depth_scale = rs_get_device_depth_scale (rs_device_, &rs_error_); - check_error ();// Default value is 0.001 + checkError ();// Default value is 0.001 // Fill the PointCloud2 fields. for (int y = 0; y < z_intrinsic.height; y++) @@ -901,7 +916,7 @@ namespace realsense_camera rs_extrinsics z_extrinsic; // extrinsics are offsets between the cameras - rs_get_device_extrinsics (rs_device_, RS_STREAM_DEPTH, RS_STREAM_COLOR, &z_extrinsic, &rs_error_); check_error (); + rs_get_device_extrinsics (rs_device_, RS_STREAM_DEPTH, RS_STREAM_COLOR, &z_extrinsic, &rs_error_); checkError (); ros::Duration sleeper(0.1); // 100ms diff --git a/camera/src/realsense_camera_nodelet.h b/camera/src/realsense_camera_nodelet.h index 645c2433e0..df105b6fbf 100644 --- a/camera/src/realsense_camera_nodelet.h +++ b/camera/src/realsense_camera_nodelet.h @@ -165,11 +165,11 @@ class RealsenseNodelet: public nodelet::Nodelet boost::shared_ptr> dynamic_reconf_server_; // Member Functions. - void enable_color_stream(); - void enable_depth_stream(); - void enable_infrared_stream(); - void enable_infrared2_stream(); - void check_error(); + void enableColorStream(); + void enableDepthStream(); + void enableInfraredStream(); + void enableInfrared2Stream(); + void checkError(); void fetchCalibData(); void prepareStreamCalibData(rs_stream calib_data); void prepareStreamData(rs_stream rs_strm); diff --git a/camera/test/realsense_camera_test_node.cpp b/camera/test/realsense_camera_test_node.cpp index 1daeb29b0b..06c5522c6b 100644 --- a/camera/test/realsense_camera_test_node.cpp +++ b/camera/test/realsense_camera_test_node.cpp @@ -267,10 +267,14 @@ TEST (RealsenseTests, testIsDepthStreamEnabled) if (enable_depth) { EXPECT_TRUE (depth_recv); + EXPECT_TRUE (infrared1_recv); + EXPECT_TRUE (infrared2_recv); } else { EXPECT_FALSE (depth_recv); + EXPECT_FALSE (infrared1_recv); + EXPECT_FALSE (infrared2_recv); } } @@ -329,7 +333,7 @@ TEST (RealsenseTests, testDepthCameraInfo) TEST (RealsenseTests, testInfrared1Stream) { - if (enable_infrared1) + if (enable_depth) { EXPECT_TRUE (infrared1_avg > 0); EXPECT_TRUE (infrared1_recv); @@ -350,7 +354,7 @@ TEST (RealsenseTests, testInfrared1Stream) TEST (RealsenseTests, testInfrared1Resolution) { - if (enable_infrared1) + if (enable_depth) { if (depth_width_exp > 0) { @@ -365,7 +369,7 @@ TEST (RealsenseTests, testInfrared1Resolution) TEST (RealsenseTests, testInfrared1CameraInfo) { - if (enable_infrared1) + if (enable_depth) { EXPECT_EQ (infrared1_width_recv, inf1_caminfo_width_recv); EXPECT_EQ (infrared1_height_recv, inf1_caminfo_height_recv); @@ -381,7 +385,7 @@ TEST (RealsenseTests, testInfrared1CameraInfo) TEST (RealsenseTests, testInfrared2Stream) { - if (enable_infrared2) + if (enable_depth) { EXPECT_TRUE (infrared2_avg > 0); EXPECT_TRUE (infrared2_recv); @@ -394,7 +398,7 @@ TEST (RealsenseTests, testInfrared2Stream) TEST (RealsenseTests, testInfrared2Resolution) { - if (enable_infrared2) + if (enable_depth) { if (depth_width_exp > 0) { @@ -409,7 +413,7 @@ TEST (RealsenseTests, testInfrared2Resolution) TEST (RealsenseTests, testInfrared2CameraInfo) { - if (enable_infrared2) + if (enable_depth) { EXPECT_EQ (infrared2_width_recv, inf2_caminfo_width_recv); EXPECT_EQ (infrared2_height_recv, inf2_caminfo_height_recv); From b9a139d5008d9d527eea2b98a86060447d73129d Mon Sep 17 00:00:00 2001 From: Rajvi Jingar Date: Mon, 14 Mar 2016 17:07:03 -0500 Subject: [PATCH 062/124] Update realsense_camera_test_node.h removed enable_infrared1 and enable_infrared2 flags --- camera/test/realsense_camera_test_node.h | 2 -- 1 file changed, 2 deletions(-) diff --git a/camera/test/realsense_camera_test_node.h b/camera/test/realsense_camera_test_node.h index ab06dbe8fc..5e9dc5c6aa 100644 --- a/camera/test/realsense_camera_test_node.h +++ b/camera/test/realsense_camera_test_node.h @@ -80,8 +80,6 @@ uint32_t infrared2_step_exp; // Expected infrared2 step. bool enable_color = true; bool enable_depth = true; -bool enable_infrared1 = true; -bool enable_infrared2 = true; bool enable_pointcloud = true; std::string depth_encoding_exp; // Expected depth encoding. From b2946e01f5f7279f24ab976892ba2705b19b4334 Mon Sep 17 00:00:00 2001 From: Rajvi Jingar Date: Tue, 15 Mar 2016 14:31:55 -0500 Subject: [PATCH 063/124] Update camera_params.cfg --- camera/cfg/camera_params.cfg | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/camera/cfg/camera_params.cfg b/camera/cfg/camera_params.cfg index 9d60718b21..0dca975f71 100755 --- a/camera/cfg/camera_params.cfg +++ b/camera/cfg/camera_params.cfg @@ -7,7 +7,7 @@ from dynamic_reconfigure.parameter_generator_catkin import * gen = ParameterGenerator() # Name Type Level Description Default Min Max -gen.add("ENABLE_DEPTH", bool_t, 0, "Enable Depth", True) +gen.add("ENABLE_DEPTH", bool_t, 0, "Enable Depth", True) gen.add("COLOR_BACKLIGHT_COMPENSATION", int_t, 0, "Backlight Compensation", 1, 0, 4) gen.add("COLOR_BRIGHTNESS", int_t, 0, "Brightness", 56, 0, 255) gen.add("COLOR_CONTRAST", int_t, 0, "Contrast", 32, 16, 64) From 56061ee208968b1e357eb54b4e2fd65a7a198824 Mon Sep 17 00:00:00 2001 From: rjingar Date: Tue, 15 Mar 2016 12:55:10 -0700 Subject: [PATCH 064/124] Fixec cfg formatting --- camera/cfg/camera_params.cfg | 40 ++++++++++++++++++------------------ 1 file changed, 20 insertions(+), 20 deletions(-) diff --git a/camera/cfg/camera_params.cfg b/camera/cfg/camera_params.cfg index 0dca975f71..abebab2fe0 100755 --- a/camera/cfg/camera_params.cfg +++ b/camera/cfg/camera_params.cfg @@ -7,25 +7,25 @@ from dynamic_reconfigure.parameter_generator_catkin import * gen = ParameterGenerator() # Name Type Level Description Default Min Max -gen.add("ENABLE_DEPTH", bool_t, 0, "Enable Depth", True) -gen.add("COLOR_BACKLIGHT_COMPENSATION", int_t, 0, "Backlight Compensation", 1, 0, 4) -gen.add("COLOR_BRIGHTNESS", int_t, 0, "Brightness", 56, 0, 255) -gen.add("COLOR_CONTRAST", int_t, 0, "Contrast", 32, 16, 64) -gen.add("COLOR_GAIN", int_t, 0, "Gain", 32, 0, 256) -gen.add("COLOR_GAMMA", int_t, 0, "Gamma", 220, 100, 280) -gen.add("COLOR_HUE", int_t, 0, "Hue", 0, -2200, 2200) -gen.add("COLOR_SATURATION", int_t, 0, "Saturation", 128, 0, 255) -gen.add("COLOR_SHARPNESS", int_t, 0, "Sharpness", 0, 0, 7) -gen.add("COLOR_WHITE_BALANCE", int_t, 0, "White Balance", 6500, 2000, 8000) -gen.add("COLOR_ENABLE_AUTO_WHITE_BALANCE", int_t, 0, "Enable Auto White Balance", 1, 0, 1) -gen.add("R200_LR_AUTO_EXPOSURE_ENABLED", int_t, 0, "LR Auto Exposure Enabled", 0, 0, 1) -gen.add("R200_LR_GAIN", int_t, 0, "LR Gain", 400, 100, 6399) -gen.add("R200_LR_EXPOSURE", int_t, 0, "LR Exposure", 164, 1, 164) -gen.add("R200_EMITTER_ENABLED", int_t, 0, "Emitter Enabled", 1, 0, 1) -gen.add("R200_DISPARITY_MULTIPLIER", int_t, 0, "Disparity Multiplier", 32, 1, 1000) -gen.add("R200_AUTO_EXPOSURE_TOP_EDGE", int_t, 0, "Auto Exposure Top Edge", 0, 0, 479) -gen.add("R200_AUTO_EXPOSURE_BOTTOM_EDGE", int_t, 0, "Auto Exposure Bottom Edge", 479, 0, 479) -gen.add("R200_AUTO_EXPOSURE_LEFT_EDGE", int_t, 0, "Auto Exposure Left Edge", 0, 0, 639) -gen.add("R200_AUTO_EXPOSURE_RIGHT_EDGE", int_t, 0, "Auto Exposure Right Edge", 639, 0, 639) +gen.add("ENABLE_DEPTH", bool_t, 0, "Enable Depth", True) +gen.add("COLOR_BACKLIGHT_COMPENSATION", int_t, 0, "Backlight Compensation", 1, 0, 4) +gen.add("COLOR_BRIGHTNESS", int_t, 0, "Brightness", 56, 0, 255) +gen.add("COLOR_CONTRAST", int_t, 0, "Contrast", 32, 16, 64) +gen.add("COLOR_GAIN", int_t, 0, "Gain", 32, 0, 256) +gen.add("COLOR_GAMMA", int_t, 0, "Gamma", 220, 100, 280) +gen.add("COLOR_HUE", int_t, 0, "Hue", 0, -2200, 2200) +gen.add("COLOR_SATURATION", int_t, 0, "Saturation", 128, 0, 255) +gen.add("COLOR_SHARPNESS", int_t, 0, "Sharpness", 0, 0, 7) +gen.add("COLOR_WHITE_BALANCE", int_t, 0, "White Balance", 6500, 2000, 8000) +gen.add("COLOR_ENABLE_AUTO_WHITE_BALANCE", int_t, 0, "Enable Auto White Balance", 1, 0, 1) +gen.add("R200_LR_AUTO_EXPOSURE_ENABLED", int_t, 0, "LR Auto Exposure Enabled", 0, 0, 1) +gen.add("R200_LR_GAIN", int_t, 0, "LR Gain", 400, 100, 6399) +gen.add("R200_LR_EXPOSURE", int_t, 0, "LR Exposure", 164, 1, 164) +gen.add("R200_EMITTER_ENABLED", int_t, 0, "Emitter Enabled", 1, 0, 1) +gen.add("R200_DISPARITY_MULTIPLIER", int_t, 0, "Disparity Multiplier", 32, 1, 1000) +gen.add("R200_AUTO_EXPOSURE_TOP_EDGE", int_t, 0, "Auto Exposure Top Edge", 0, 0, 479) +gen.add("R200_AUTO_EXPOSURE_BOTTOM_EDGE", int_t, 0, "Auto Exposure Bottom Edge", 479, 0, 479) +gen.add("R200_AUTO_EXPOSURE_LEFT_EDGE", int_t, 0, "Auto Exposure Left Edge", 0, 0, 639) +gen.add("R200_AUTO_EXPOSURE_RIGHT_EDGE", int_t, 0, "Auto Exposure Right Edge", 639, 0, 639) exit(gen.generate(PACKAGE, "realsense_camera", "camera_params")) From d4f9e56d0ba091965b9fef72a9872dec5708959f Mon Sep 17 00:00:00 2001 From: rjingar Date: Fri, 4 Mar 2016 16:16:34 -0800 Subject: [PATCH 065/124] Add dynamically enable/disable depth stream code --- camera/cfg/camera_params.cfg | 1 + camera/src/realsense_camera_nodelet.cpp | 277 ++++++++++++++++-------- camera/src/realsense_camera_nodelet.h | 4 + 3 files changed, 189 insertions(+), 93 deletions(-) diff --git a/camera/cfg/camera_params.cfg b/camera/cfg/camera_params.cfg index ce1d2376f7..9d60718b21 100755 --- a/camera/cfg/camera_params.cfg +++ b/camera/cfg/camera_params.cfg @@ -7,6 +7,7 @@ from dynamic_reconfigure.parameter_generator_catkin import * gen = ParameterGenerator() # Name Type Level Description Default Min Max +gen.add("ENABLE_DEPTH", bool_t, 0, "Enable Depth", True) gen.add("COLOR_BACKLIGHT_COMPENSATION", int_t, 0, "Backlight Compensation", 1, 0, 4) gen.add("COLOR_BRIGHTNESS", int_t, 0, "Brightness", 56, 0, 255) gen.add("COLOR_CONTRAST", int_t, 0, "Contrast", 32, 16, 64) diff --git a/camera/src/realsense_camera_nodelet.cpp b/camera/src/realsense_camera_nodelet.cpp index f5a64d4997..61d9db400e 100644 --- a/camera/src/realsense_camera_nodelet.cpp +++ b/camera/src/realsense_camera_nodelet.cpp @@ -92,6 +92,9 @@ namespace realsense_camera frame_id_[RS_STREAM_INFRARED] = IR1_DEF_FRAME; frame_id_[RS_STREAM_INFRARED2] = IR2_DEF_FRAME; + for (int i = 0; i < STREAM_COUNT; ++i) + camera_info_[i] = NULL; + ros::NodeHandle & nh = getNodeHandle (); // Set up the topics. @@ -101,28 +104,18 @@ namespace realsense_camera getConfigValues (camera_configuration_); // Advertise the various topics and services. + // Advertise color stream only if color parameter is set. + camera_publisher_[RS_STREAM_COLOR] = it.advertiseCamera (COLOR_TOPIC, 1); // Advertise depth and infrared streams only if depth parameter is set. - if (enable_depth_ == true) + camera_publisher_[RS_STREAM_DEPTH] = it.advertiseCamera (DEPTH_TOPIC, 1); + camera_publisher_[RS_STREAM_INFRARED] = it.advertiseCamera (IR1_TOPIC, 1); + if (camera_.find (R200) != std::string::npos) { - camera_publisher_[RS_STREAM_DEPTH] = it.advertiseCamera (DEPTH_TOPIC, 1); - camera_publisher_[RS_STREAM_INFRARED] = it.advertiseCamera (IR1_TOPIC, 1); - if (camera_.find (R200) != std::string::npos) - { - camera_publisher_[RS_STREAM_INFRARED2] = it.advertiseCamera (IR2_TOPIC, 1); - } - - // Advertise pointcloud only if pointcloud parameter is set. - if (enable_pointcloud_ == true) - { - pointcloud_publisher_ = nh.advertise < sensor_msgs::PointCloud2 > (PC_TOPIC, 1); - } + camera_publisher_[RS_STREAM_INFRARED2] = it.advertiseCamera (IR2_TOPIC, 1); } - // Advertise color stream only if color parameter is set. - if (enable_color_ == true) - { - camera_publisher_[RS_STREAM_COLOR] = it.advertiseCamera (COLOR_TOPIC, 1); - } + pointcloud_publisher_ = nh.advertise < sensor_msgs::PointCloud2 > (PC_TOPIC, 1); + get_options_service_ = nh.advertiseService (SETTINGS_SERVICE, &RealsenseNodelet::getCameraSettings, this); @@ -156,6 +149,90 @@ namespace realsense_camera /* *Private Methods. */ + void RealsenseNodelet::enable_color_stream() + { + // Enable streams. + if (mode_.compare ("manual") == 0) + { + ROS_INFO_STREAM ("RealSense Camera - Enabling Color Stream: manual mode"); + rs_enable_stream (rs_device_, RS_STREAM_COLOR, color_width_, color_height_, COLOR_FORMAT, color_fps_, &rs_error_); + check_error (); + } + else + { + ROS_INFO_STREAM ("RealSense Camera - Enabling Color Stream: preset mode"); + rs_enable_stream_preset (rs_device_, RS_STREAM_COLOR, RS_PRESET_BEST_QUALITY, &rs_error_); check_error (); + } + + uint32_t stream_index = (uint32_t) RS_STREAM_COLOR; + if(camera_info_[stream_index] == NULL) { + prepareStreamCalibData (RS_STREAM_COLOR); + } + } + + void RealsenseNodelet::enable_depth_stream() + { + // Enable streams. + if (mode_.compare ("manual") == 0) + { + ROS_INFO_STREAM ("RealSense Camera - Enabling Depth Stream: manual mode"); + rs_enable_stream (rs_device_, RS_STREAM_DEPTH, depth_width_, depth_height_, DEPTH_FORMAT, depth_fps_, &rs_error_); + check_error (); + } + else + { + ROS_INFO_STREAM ("RealSense Camera - Enabling Depth Stream: preset mode"); + rs_enable_stream_preset (rs_device_, RS_STREAM_DEPTH, RS_PRESET_BEST_QUALITY, &rs_error_); check_error (); + } + + uint32_t stream_index = (uint32_t) RS_STREAM_DEPTH; + if(camera_info_[stream_index] == NULL) { + prepareStreamCalibData (RS_STREAM_DEPTH); + } + } + + void RealsenseNodelet::enable_infrared_stream() + { + // Enable streams. + if (mode_.compare ("manual") == 0) + { + ROS_INFO_STREAM ("RealSense Camera - Enabling Infrared Stream: manual mode"); + rs_enable_stream (rs_device_, RS_STREAM_INFRARED, depth_width_, depth_height_, IR1_FORMAT, depth_fps_, &rs_error_); + check_error (); + } + else + { + ROS_INFO_STREAM ("RealSense Camera - Enabling Infrared Stream: preset mode"); + rs_enable_stream_preset (rs_device_, RS_STREAM_INFRARED, RS_PRESET_BEST_QUALITY, &rs_error_); check_error (); + } + + uint32_t stream_index = (uint32_t) RS_STREAM_INFRARED; + if(camera_info_[stream_index] == NULL) { + prepareStreamCalibData (RS_STREAM_INFRARED); + } + } + + void RealsenseNodelet::enable_infrared2_stream() + { + // Enable streams. + if (mode_.compare ("manual") == 0) + { + ROS_INFO_STREAM ("RealSense Camera - Enabling Infrared2 Stream: manual mode"); + rs_enable_stream (rs_device_, RS_STREAM_INFRARED2, depth_width_, depth_height_, IR2_FORMAT, depth_fps_, 0); + } + else + { + ROS_INFO_STREAM ("RealSense Camera - Enabling Infrared2 Stream: preset mode"); + rs_enable_stream_preset (rs_device_, RS_STREAM_INFRARED2, RS_PRESET_BEST_QUALITY, 0); + } + uint32_t stream_index = (uint32_t) RS_STREAM_INFRARED2; + if(camera_info_[stream_index] == NULL) { + prepareStreamCalibData (RS_STREAM_INFRARED2); + } + } + + + void RealsenseNodelet::configCallback(realsense_camera::camera_paramsConfig &config, uint32_t level) { rs_set_device_option(rs_device_, RS_OPTION_COLOR_BACKLIGHT_COMPENSATION, config.COLOR_BACKLIGHT_COMPENSATION, 0); @@ -203,7 +280,15 @@ namespace realsense_camera edge_values_[3] = config.R200_AUTO_EXPOSURE_BOTTOM_EDGE; rs_set_device_options(rs_device_, edge_options_, 4, edge_values_, 0); - } + } + + if(config.ENABLE_DEPTH == false) { + enable_depth_ = false; + } + else { + enable_depth_ = true; + } + } void RealsenseNodelet::check_error () @@ -254,7 +339,7 @@ namespace realsense_camera ROS_INFO_STREAM ("RealSense Camera - Number of cameras connected: " << num_of_cameras); ROS_INFO_STREAM ("RealSense Camera - Firmware version: " << - rs_get_device_firmware_version (rs_device_, &rs_error_)); + rs_get_device_firmware_version (rs_device_, &rs_error_)); check_error (); ROS_INFO_STREAM ("RealSense Camera - Name: " << rs_get_device_name (rs_device_, &rs_error_)); check_error (); @@ -262,36 +347,16 @@ namespace realsense_camera check_error (); // Enable streams. - if (enable_depth_ == true) + if (enable_color_ == true) { - if (mode_.compare ("manual") == 0) - { - ROS_INFO_STREAM ("RealSense Camera - Enabling Depth Stream: manual mode"); - rs_enable_stream (rs_device_, RS_STREAM_DEPTH, depth_width_, depth_height_, DEPTH_FORMAT, depth_fps_, &rs_error_); - rs_enable_stream (rs_device_, RS_STREAM_INFRARED, depth_width_, depth_height_, IR1_FORMAT, depth_fps_, &rs_error_); - rs_enable_stream (rs_device_, RS_STREAM_INFRARED2, depth_width_, depth_height_, IR2_FORMAT, depth_fps_, 0); - } - else - { - ROS_INFO_STREAM ("RealSense Camera - Enabling Depth Stream: preset mode"); - rs_enable_stream_preset (rs_device_, RS_STREAM_DEPTH, RS_PRESET_BEST_QUALITY, &rs_error_); check_error (); - rs_enable_stream_preset (rs_device_, RS_STREAM_INFRARED, RS_PRESET_BEST_QUALITY, &rs_error_); check_error (); - rs_enable_stream_preset (rs_device_, RS_STREAM_INFRARED2, RS_PRESET_BEST_QUALITY, 0); - } + enable_color_stream(); } - if (enable_color_ == true) + if (enable_depth_ == true) { - if (mode_.compare ("manual") == 0) - { - ROS_INFO_STREAM ("RealSense Camera - Enabling Color Stream: manual mode"); - rs_enable_stream (rs_device_, RS_STREAM_COLOR, color_width_, color_height_, COLOR_FORMAT, color_fps_, &rs_error_); - } - else - { - ROS_INFO_STREAM ("RealSense Camera - Enabling Color Stream: preset mode"); - rs_enable_stream_preset (rs_device_, RS_STREAM_COLOR, RS_PRESET_BEST_QUALITY, &rs_error_); check_error (); - } + enable_depth_stream(); + enable_infrared_stream(); + enable_infrared2_stream(); } for (int i = 0; i < RS_OPTION_COUNT; ++i) @@ -299,7 +364,7 @@ namespace realsense_camera option_str o = { (rs_option) i}; - if (!rs_device_supports_option (rs_device_, o.opt, &rs_error_)) + if (!rs_device_supports_option (rs_device_, o.opt, 0)) { continue; } @@ -318,6 +383,7 @@ namespace realsense_camera // Start device. rs_start_device (rs_device_, &rs_error_); + check_error (); is_device_started_ = true; @@ -334,26 +400,12 @@ namespace realsense_camera // Prepare camera for enabled streams (color/depth/infrared/infrared2). fillStreamEncoding (); - if (rs_is_stream_enabled (rs_device_, RS_STREAM_COLOR, 0)) - { - image_[(uint32_t) RS_STREAM_COLOR] = cv::Mat (color_height_, color_width_, CV_8UC3, cv::Scalar (0, 0, 0)); - prepareStreamCalibData (RS_STREAM_COLOR); - } - - if (rs_is_stream_enabled (rs_device_, RS_STREAM_DEPTH, 0)) + image_[(uint32_t) RS_STREAM_COLOR] = cv::Mat (color_height_, color_width_, CV_8UC3, cv::Scalar (0, 0, 0)); + image_[(uint32_t) RS_STREAM_DEPTH] = cv::Mat (depth_height_, depth_width_, CV_16UC1, cv::Scalar (0)); + image_[(uint32_t) RS_STREAM_INFRARED] = cv::Mat (depth_height_, depth_width_, CV_8UC1, cv::Scalar (0)); + if (camera_.find (R200) != std::string::npos) { - // Define message. - image_[(uint32_t) RS_STREAM_DEPTH] = cv::Mat (depth_height_, depth_width_, CV_16UC1, cv::Scalar (0)); - prepareStreamCalibData (RS_STREAM_DEPTH); - - image_[(uint32_t) RS_STREAM_INFRARED] = cv::Mat (depth_height_, depth_width_, CV_8UC1, cv::Scalar (0)); - prepareStreamCalibData (RS_STREAM_INFRARED); - - if (rs_is_stream_enabled (rs_device_, RS_STREAM_INFRARED2, 0)) - { image_[(uint32_t) RS_STREAM_INFRARED2] = cv::Mat (depth_height_, depth_width_, CV_8UC1, cv::Scalar (0)); - prepareStreamCalibData (RS_STREAM_INFRARED2); - } } } @@ -435,7 +487,7 @@ namespace realsense_camera { option_str o = { (rs_option) i}; - if (!rs_device_supports_option (rs_device_, o.opt, &rs_error_)) + if (!rs_device_supports_option (rs_device_, o.opt, 0)) { continue; } @@ -646,45 +698,84 @@ namespace realsense_camera */ void RealsenseNodelet::publishStreams () { - rs_wait_for_frames (rs_device_, &rs_error_); - check_error (); - time_stamp_ = ros::Time::now (); - - for (int stream_index = 0; stream_index < STREAM_COUNT; ++stream_index) + if(enable_depth_ == false && rs_is_stream_enabled (rs_device_, RS_STREAM_DEPTH, 0) == 1) { - // Publish image stream only if there is at least one subscriber. - if (camera_publisher_[stream_index].getNumSubscribers () > 0) + if(rs_is_device_streaming(rs_device_, 0) == 1) { - prepareStreamData ((rs_stream) stream_index); - - sensor_msgs::ImagePtr msg = cv_bridge::CvImage (std_msgs::Header (), - stream_encoding_[stream_index], - image_[stream_index]).toImageMsg (); + rs_stop_device (rs_device_, &rs_error_); check_error (); + ROS_INFO_STREAM ("RealSense Camera - Device Stopped"); + } - msg->header.frame_id = frame_id_[stream_index]; - msg->header.stamp = time_stamp_; // Publish timestamp to synchronize frames. - msg->width = image_[stream_index].cols; - msg->height = image_[stream_index].rows; - msg->is_bigendian = false; - msg->step = stream_step_[stream_index]; + rs_disable_stream(rs_device_, RS_STREAM_DEPTH, &rs_error_); check_error (); + ROS_INFO_STREAM ("RealSense Camera - Depth Stream Disabled"); - camera_info_ptr_[stream_index]->header.stamp = msg->header.stamp; - camera_publisher_[stream_index].publish (msg, camera_info_ptr_[stream_index]); + if(rs_is_device_streaming(rs_device_, 0) == 0) + { + rs_start_device (rs_device_, &rs_error_);check_error (); + ROS_INFO_STREAM ("RealSense Camera - Device Started"); + } + } + + if(enable_depth_ == true && rs_is_stream_enabled (rs_device_, RS_STREAM_DEPTH, 0) == 0) + { + if(rs_is_device_streaming(rs_device_, 0) == 1) + { + rs_stop_device (rs_device_, &rs_error_); check_error (); + ROS_INFO_STREAM ("RealSense Camera - Device Stopped"); + } + + enable_depth_stream(); + + if(rs_is_device_streaming(rs_device_, 0) == 0) + { + rs_start_device (rs_device_, &rs_error_); check_error (); + ROS_INFO_STREAM ("RealSense Camera - Device Started"); } } - if (pointcloud_publisher_.getNumSubscribers () > 0 && rs_is_stream_enabled (rs_device_, RS_STREAM_DEPTH, 0) - && enable_pointcloud_ == true) + if(rs_is_device_streaming(rs_device_, 0) == 1) { - if (camera_publisher_[(uint32_t) RS_STREAM_DEPTH].getNumSubscribers () <= 0) + rs_wait_for_frames (rs_device_, &rs_error_); + check_error (); + time_stamp_ = ros::Time::now (); + + for (int stream_index = 0; stream_index < STREAM_COUNT; ++stream_index) { - prepareStreamData (RS_STREAM_DEPTH); + // Publish image stream only if there is at least one subscriber. + if (camera_publisher_[stream_index].getNumSubscribers () > 0 && + rs_is_stream_enabled (rs_device_, (rs_stream) stream_index, 0) == 1) + { + prepareStreamData ((rs_stream) stream_index); + + sensor_msgs::ImagePtr msg = cv_bridge::CvImage (std_msgs::Header (), + stream_encoding_[stream_index], + image_[stream_index]).toImageMsg (); + + msg->header.frame_id = frame_id_[stream_index]; + msg->header.stamp = time_stamp_; // Publish timestamp to synchronize frames. + msg->width = image_[stream_index].cols; + msg->height = image_[stream_index].rows; + msg->is_bigendian = false; + msg->step = stream_step_[stream_index]; + + camera_info_ptr_[stream_index]->header.stamp = msg->header.stamp; + camera_publisher_[stream_index].publish (msg, camera_info_ptr_[stream_index]); + } } - if (camera_publisher_[(uint32_t) RS_STREAM_COLOR].getNumSubscribers () <= 0) + + if (pointcloud_publisher_.getNumSubscribers () > 0 && rs_is_stream_enabled (rs_device_, RS_STREAM_DEPTH, 0) == 1 + && enable_pointcloud_ == true) { - prepareStreamData (RS_STREAM_COLOR); + if (camera_publisher_[(uint32_t) RS_STREAM_DEPTH].getNumSubscribers () <= 0) + { + prepareStreamData (RS_STREAM_DEPTH); + } + if (camera_publisher_[(uint32_t) RS_STREAM_COLOR].getNumSubscribers () <= 0) + { + prepareStreamData (RS_STREAM_COLOR); + } + publishPointCloud (image_[(uint32_t) RS_STREAM_COLOR]); } - publishPointCloud (image_[(uint32_t) RS_STREAM_COLOR]); } } diff --git a/camera/src/realsense_camera_nodelet.h b/camera/src/realsense_camera_nodelet.h index dd27b3f8a1..645c2433e0 100644 --- a/camera/src/realsense_camera_nodelet.h +++ b/camera/src/realsense_camera_nodelet.h @@ -165,6 +165,10 @@ class RealsenseNodelet: public nodelet::Nodelet boost::shared_ptr> dynamic_reconf_server_; // Member Functions. + void enable_color_stream(); + void enable_depth_stream(); + void enable_infrared_stream(); + void enable_infrared2_stream(); void check_error(); void fetchCalibData(); void prepareStreamCalibData(rs_stream calib_data); From 9886939bab9f1226ed7201600ae241a340cf3630 Mon Sep 17 00:00:00 2001 From: rjingar Date: Thu, 10 Mar 2016 17:53:40 -0800 Subject: [PATCH 066/124] Add unit tests for Enable/disable depth stream --- camera/test/realsense_camera_test_node.cpp | 24 ++++++++++++++++------ camera/test/realsense_camera_test_node.h | 2 ++ 2 files changed, 20 insertions(+), 6 deletions(-) diff --git a/camera/test/realsense_camera_test_node.cpp b/camera/test/realsense_camera_test_node.cpp index 2515ab1bee..7938aca0f5 100644 --- a/camera/test/realsense_camera_test_node.cpp +++ b/camera/test/realsense_camera_test_node.cpp @@ -300,6 +300,18 @@ TEST (RealsenseTests, testColorCameraInfo) } } +TEST (RealsenseTests, testIsDepthStreamEnabled) +{ + if (enable_depth) + { + EXPECT_TRUE (depth_recv); + } + else + { + EXPECT_FALSE (depth_recv); + } +} + TEST (RealsenseTests, testDepthStream) { if (enable_depth) @@ -370,7 +382,7 @@ TEST (RealsenseTests, testDepthCameraInfo) TEST (RealsenseTests, testInfrared1Stream) { - if (enable_depth) + if (enable_infrared1) { EXPECT_TRUE (infrared1_avg > 0); EXPECT_TRUE (infrared1_recv); @@ -391,7 +403,7 @@ TEST (RealsenseTests, testInfrared1Stream) TEST (RealsenseTests, testInfrared1Resolution) { - if (enable_depth) + if (enable_infrared1) { if (depth_width_exp > 0) { @@ -406,7 +418,7 @@ TEST (RealsenseTests, testInfrared1Resolution) TEST (RealsenseTests, testInfrared1CameraInfo) { - if (enable_depth) + if (enable_infrared1) { EXPECT_EQ (infrared1_width_recv, inf1_caminfo_width_recv); EXPECT_EQ (infrared1_height_recv, inf1_caminfo_height_recv); @@ -437,7 +449,7 @@ TEST (RealsenseTests, testInfrared1CameraInfo) TEST (RealsenseTests, testInfrared2Stream) { - if (enable_depth) + if (enable_infrared2) { EXPECT_TRUE (infrared2_avg > 0); EXPECT_TRUE (infrared2_recv); @@ -450,7 +462,7 @@ TEST (RealsenseTests, testInfrared2Stream) TEST (RealsenseTests, testInfrared2Resolution) { - if (enable_depth) + if (enable_infrared2) { if (depth_width_exp > 0) { @@ -465,7 +477,7 @@ TEST (RealsenseTests, testInfrared2Resolution) TEST (RealsenseTests, testInfrared2CameraInfo) { - if (enable_depth) + if (enable_infrared2) { EXPECT_EQ (infrared2_width_recv, inf2_caminfo_width_recv); EXPECT_EQ (infrared2_height_recv, inf2_caminfo_height_recv); diff --git a/camera/test/realsense_camera_test_node.h b/camera/test/realsense_camera_test_node.h index df3cc4049a..395f196d34 100644 --- a/camera/test/realsense_camera_test_node.h +++ b/camera/test/realsense_camera_test_node.h @@ -80,6 +80,8 @@ uint32_t infrared2_step_exp; // Expected infrared2 step. bool enable_color = true; bool enable_depth = true; +bool enable_infrared1 = true; +bool enable_infrared2 = true; bool enable_pointcloud = true; std::string depth_encoding_exp; // Expected depth encoding. From 3394f4057d39468a857a8e775f1a59dcecf9cbff Mon Sep 17 00:00:00 2001 From: rjingar Date: Mon, 14 Mar 2016 08:39:58 -0700 Subject: [PATCH 067/124] Added Enable/disable infrared streams along with depth stream --- camera/src/realsense_camera_nodelet.cpp | 10 +++++++++- 1 file changed, 9 insertions(+), 1 deletion(-) diff --git a/camera/src/realsense_camera_nodelet.cpp b/camera/src/realsense_camera_nodelet.cpp index 61d9db400e..d778f23c4e 100644 --- a/camera/src/realsense_camera_nodelet.cpp +++ b/camera/src/realsense_camera_nodelet.cpp @@ -709,6 +709,12 @@ namespace realsense_camera rs_disable_stream(rs_device_, RS_STREAM_DEPTH, &rs_error_); check_error (); ROS_INFO_STREAM ("RealSense Camera - Depth Stream Disabled"); + rs_disable_stream(rs_device_, RS_STREAM_INFRARED, &rs_error_); check_error (); + ROS_INFO_STREAM ("RealSense Camera - Infrared1 stream Disabled"); + + rs_disable_stream(rs_device_, RS_STREAM_INFRARED2, &rs_error_); check_error (); + ROS_INFO_STREAM ("RealSense Camera - Infrared2 stream Disabled"); + if(rs_is_device_streaming(rs_device_, 0) == 0) { rs_start_device (rs_device_, &rs_error_);check_error (); @@ -725,7 +731,9 @@ namespace realsense_camera } enable_depth_stream(); - + enable_infrared_stream(); + enable_infrared2_stream(); + if(rs_is_device_streaming(rs_device_, 0) == 0) { rs_start_device (rs_device_, &rs_error_); check_error (); From 3202a2fd49194894efff176b4b37ce39df77fdef Mon Sep 17 00:00:00 2001 From: rjingar Date: Mon, 14 Mar 2016 14:58:42 -0700 Subject: [PATCH 068/124] Added Enable/disable infrared streams along with depth stream. --- camera/README.md | 7 +- camera/src/realsense_camera_nodelet.cpp | 109 ++++++++++++--------- camera/src/realsense_camera_nodelet.h | 10 +- camera/test/realsense_camera_test_node.cpp | 16 +-- 4 files changed, 83 insertions(+), 59 deletions(-) diff --git a/camera/README.md b/camera/README.md index 46959655a1..f804bfd891 100644 --- a/camera/README.md +++ b/camera/README.md @@ -88,7 +88,7 @@ Infrared2 camera depth_fps (int, default: 60) Specify the depth camera FPS enable_depth (bool, default: true) - Specify if to enable or not the depth camera. + Specify if to enable or not the depth and infrared camera. enable_color (bool, default: true) Specify if to enable or not the color camera. enable_pointcloud (bool, default: true) @@ -141,6 +141,11 @@ To get supported camera options with current value set. It returns string in opt R200_AUTO_EXPOSURE_LEFT_EDGE R200_AUTO_EXPOSURE_RIGHT_EDGE + Enable/Disable Stream: + ENABLE_DEPTH + Check or uncheck the option to disable/enable depth and infrared streams dynamically. + Note: Infrared streams will be enabled or disabled along with depth stream. + Use rqt_reconfigure GUI to view and edit the parameters that are accessible via dynamic_reconfigure. Command to launch GUI: diff --git a/camera/src/realsense_camera_nodelet.cpp b/camera/src/realsense_camera_nodelet.cpp index d778f23c4e..13a799ab24 100644 --- a/camera/src/realsense_camera_nodelet.cpp +++ b/camera/src/realsense_camera_nodelet.cpp @@ -58,7 +58,7 @@ namespace realsense_camera { rs_stop_device (rs_device_, 0); rs_delete_context (rs_context_, &rs_error_); - check_error (); + checkError (); } ROS_INFO_STREAM ("RealSense Camera - Stopping camera nodelet."); @@ -149,19 +149,19 @@ namespace realsense_camera /* *Private Methods. */ - void RealsenseNodelet::enable_color_stream() + void RealsenseNodelet::enableColorStream() { // Enable streams. if (mode_.compare ("manual") == 0) { ROS_INFO_STREAM ("RealSense Camera - Enabling Color Stream: manual mode"); rs_enable_stream (rs_device_, RS_STREAM_COLOR, color_width_, color_height_, COLOR_FORMAT, color_fps_, &rs_error_); - check_error (); + checkError (); } else { ROS_INFO_STREAM ("RealSense Camera - Enabling Color Stream: preset mode"); - rs_enable_stream_preset (rs_device_, RS_STREAM_COLOR, RS_PRESET_BEST_QUALITY, &rs_error_); check_error (); + rs_enable_stream_preset (rs_device_, RS_STREAM_COLOR, RS_PRESET_BEST_QUALITY, &rs_error_); checkError (); } uint32_t stream_index = (uint32_t) RS_STREAM_COLOR; @@ -170,49 +170,51 @@ namespace realsense_camera } } - void RealsenseNodelet::enable_depth_stream() + void RealsenseNodelet::enableDepthStream() { // Enable streams. if (mode_.compare ("manual") == 0) { ROS_INFO_STREAM ("RealSense Camera - Enabling Depth Stream: manual mode"); rs_enable_stream (rs_device_, RS_STREAM_DEPTH, depth_width_, depth_height_, DEPTH_FORMAT, depth_fps_, &rs_error_); - check_error (); + checkError (); } else { ROS_INFO_STREAM ("RealSense Camera - Enabling Depth Stream: preset mode"); - rs_enable_stream_preset (rs_device_, RS_STREAM_DEPTH, RS_PRESET_BEST_QUALITY, &rs_error_); check_error (); + rs_enable_stream_preset (rs_device_, RS_STREAM_DEPTH, RS_PRESET_BEST_QUALITY, &rs_error_); checkError (); } uint32_t stream_index = (uint32_t) RS_STREAM_DEPTH; - if(camera_info_[stream_index] == NULL) { + if(camera_info_[stream_index] == NULL) + { prepareStreamCalibData (RS_STREAM_DEPTH); } } - void RealsenseNodelet::enable_infrared_stream() + void RealsenseNodelet::enableInfraredStream() { // Enable streams. if (mode_.compare ("manual") == 0) { ROS_INFO_STREAM ("RealSense Camera - Enabling Infrared Stream: manual mode"); rs_enable_stream (rs_device_, RS_STREAM_INFRARED, depth_width_, depth_height_, IR1_FORMAT, depth_fps_, &rs_error_); - check_error (); + checkError (); } else { ROS_INFO_STREAM ("RealSense Camera - Enabling Infrared Stream: preset mode"); - rs_enable_stream_preset (rs_device_, RS_STREAM_INFRARED, RS_PRESET_BEST_QUALITY, &rs_error_); check_error (); + rs_enable_stream_preset (rs_device_, RS_STREAM_INFRARED, RS_PRESET_BEST_QUALITY, &rs_error_); checkError (); } uint32_t stream_index = (uint32_t) RS_STREAM_INFRARED; - if(camera_info_[stream_index] == NULL) { + if(camera_info_[stream_index] == NULL) + { prepareStreamCalibData (RS_STREAM_INFRARED); } } - void RealsenseNodelet::enable_infrared2_stream() + void RealsenseNodelet::enableInfrared2Stream() { // Enable streams. if (mode_.compare ("manual") == 0) @@ -225,8 +227,10 @@ namespace realsense_camera ROS_INFO_STREAM ("RealSense Camera - Enabling Infrared2 Stream: preset mode"); rs_enable_stream_preset (rs_device_, RS_STREAM_INFRARED2, RS_PRESET_BEST_QUALITY, 0); } + uint32_t stream_index = (uint32_t) RS_STREAM_INFRARED2; - if(camera_info_[stream_index] == NULL) { + if(camera_info_[stream_index] == NULL) + { prepareStreamCalibData (RS_STREAM_INFRARED2); } } @@ -282,16 +286,25 @@ namespace realsense_camera rs_set_device_options(rs_device_, edge_options_, 4, edge_values_, 0); } - if(config.ENABLE_DEPTH == false) { - enable_depth_ = false; + if(config.ENABLE_DEPTH == false) + { + if(enable_color_ == false) + { + ROS_INFO_STREAM ("RealSense Camera - Color stream is also disabled. Cannot disable depth stream"); + config.ENABLE_DEPTH = true; + } + else + { + enable_depth_ = false; + } } - else { + else + { enable_depth_ = true; } - } - void RealsenseNodelet::check_error () + void RealsenseNodelet::checkError () { if (rs_error_) { @@ -325,7 +338,7 @@ namespace realsense_camera } rs_context_ = rs_create_context (RS_API_VERSION, &rs_error_); - check_error (); + checkError (); int num_of_cameras = rs_get_device_count (rs_context_, NULL); if (num_of_cameras < 1) @@ -335,28 +348,28 @@ namespace realsense_camera } rs_device_ = rs_get_device (rs_context_, 0, &rs_error_); - check_error (); + checkError (); ROS_INFO_STREAM ("RealSense Camera - Number of cameras connected: " << num_of_cameras); ROS_INFO_STREAM ("RealSense Camera - Firmware version: " << rs_get_device_firmware_version (rs_device_, &rs_error_)); - check_error (); + checkError (); ROS_INFO_STREAM ("RealSense Camera - Name: " << rs_get_device_name (rs_device_, &rs_error_)); - check_error (); + checkError (); ROS_INFO_STREAM ("RealSense Camera - Serial no: " << rs_get_device_serial (rs_device_, &rs_error_)); - check_error (); + checkError (); // Enable streams. if (enable_color_ == true) { - enable_color_stream(); + enableColorStream(); } if (enable_depth_ == true) { - enable_depth_stream(); - enable_infrared_stream(); - enable_infrared2_stream(); + enableDepthStream(); + enableInfraredStream(); + enableInfrared2Stream(); } for (int i = 0; i < RS_OPTION_COUNT; ++i) @@ -383,7 +396,7 @@ namespace realsense_camera // Start device. rs_start_device (rs_device_, &rs_error_); - check_error (); + checkError (); is_device_started_ = true; @@ -417,7 +430,7 @@ namespace realsense_camera uint32_t stream_index = (uint32_t) rs_strm; rs_intrinsics intrinsic; rs_get_stream_intrinsics (rs_device_, rs_strm, &intrinsic, &rs_error_); - check_error (); + checkError (); camera_info_[stream_index] = new sensor_msgs::CameraInfo (); camera_info_ptr_[stream_index] = sensor_msgs::CameraInfoPtr (camera_info_[stream_index]); @@ -644,7 +657,7 @@ namespace realsense_camera { ROS_INFO_STREAM ("RealSense Camera - Setting" << opt_name.c_str () << " to " << config_.at (opt_name).c_str ()); rs_set_device_option (rs_device_, o.opt, atoi (config_.at (opt_name).c_str ()), &rs_error_); - check_error (); + checkError (); } cam_options.pop_back (); } @@ -702,22 +715,24 @@ namespace realsense_camera { if(rs_is_device_streaming(rs_device_, 0) == 1) { - rs_stop_device (rs_device_, &rs_error_); check_error (); + rs_stop_device (rs_device_, &rs_error_); checkError (); ROS_INFO_STREAM ("RealSense Camera - Device Stopped"); } - rs_disable_stream(rs_device_, RS_STREAM_DEPTH, &rs_error_); check_error (); + + //disable depth, infrared1 and infrared2 streams + rs_disable_stream(rs_device_, RS_STREAM_DEPTH, &rs_error_); checkError (); ROS_INFO_STREAM ("RealSense Camera - Depth Stream Disabled"); - rs_disable_stream(rs_device_, RS_STREAM_INFRARED, &rs_error_); check_error (); + rs_disable_stream(rs_device_, RS_STREAM_INFRARED, &rs_error_); checkError (); ROS_INFO_STREAM ("RealSense Camera - Infrared1 stream Disabled"); - rs_disable_stream(rs_device_, RS_STREAM_INFRARED2, &rs_error_); check_error (); + rs_disable_stream(rs_device_, RS_STREAM_INFRARED2, &rs_error_); checkError (); ROS_INFO_STREAM ("RealSense Camera - Infrared2 stream Disabled"); if(rs_is_device_streaming(rs_device_, 0) == 0) { - rs_start_device (rs_device_, &rs_error_);check_error (); + rs_start_device (rs_device_, &rs_error_);checkError (); ROS_INFO_STREAM ("RealSense Camera - Device Started"); } } @@ -726,17 +741,17 @@ namespace realsense_camera { if(rs_is_device_streaming(rs_device_, 0) == 1) { - rs_stop_device (rs_device_, &rs_error_); check_error (); + rs_stop_device (rs_device_, &rs_error_); checkError (); ROS_INFO_STREAM ("RealSense Camera - Device Stopped"); } - enable_depth_stream(); - enable_infrared_stream(); - enable_infrared2_stream(); + enableDepthStream(); + enableInfraredStream(); + enableInfrared2Stream(); if(rs_is_device_streaming(rs_device_, 0) == 0) { - rs_start_device (rs_device_, &rs_error_); check_error (); + rs_start_device (rs_device_, &rs_error_); checkError (); ROS_INFO_STREAM ("RealSense Camera - Device Started"); } } @@ -744,7 +759,7 @@ namespace realsense_camera if(rs_is_device_streaming(rs_device_, 0) == 1) { rs_wait_for_frames (rs_device_, &rs_error_); - check_error (); + checkError (); time_stamp_ = ros::Time::now (); for (int stream_index = 0; stream_index < STREAM_COUNT; ++stream_index) @@ -800,12 +815,12 @@ namespace realsense_camera rs_intrinsics z_intrinsic; rs_get_stream_intrinsics (rs_device_, RS_STREAM_DEPTH, &z_intrinsic, &rs_error_); - check_error (); + checkError (); if (enable_color_ == true) { - rs_get_stream_intrinsics (rs_device_, RS_STREAM_COLOR, &color_intrinsic, &rs_error_); check_error (); - rs_get_device_extrinsics (rs_device_, RS_STREAM_DEPTH, RS_STREAM_COLOR, &z_extrinsic, &rs_error_); check_error (); + rs_get_stream_intrinsics (rs_device_, RS_STREAM_COLOR, &color_intrinsic, &rs_error_); checkError (); + rs_get_device_extrinsics (rs_device_, RS_STREAM_DEPTH, RS_STREAM_COLOR, &z_extrinsic, &rs_error_); checkError (); } // Convert pointcloud from the camera to pointcloud object for ROS. @@ -836,7 +851,7 @@ namespace realsense_camera float depth_point[3], color_point[3], color_pixel[2], scaled_depth; unsigned char *color_data = image_color.data; const float depth_scale = rs_get_device_depth_scale (rs_device_, &rs_error_); - check_error ();// Default value is 0.001 + checkError ();// Default value is 0.001 // Fill the PointCloud2 fields. for (int y = 0; y < z_intrinsic.height; y++) @@ -911,7 +926,7 @@ namespace realsense_camera rs_extrinsics z_extrinsic; // extrinsics are offsets between the cameras - rs_get_device_extrinsics (rs_device_, RS_STREAM_DEPTH, RS_STREAM_COLOR, &z_extrinsic, &rs_error_); check_error (); + rs_get_device_extrinsics (rs_device_, RS_STREAM_DEPTH, RS_STREAM_COLOR, &z_extrinsic, &rs_error_); checkError (); ros::Duration sleeper(0.1); // 100ms diff --git a/camera/src/realsense_camera_nodelet.h b/camera/src/realsense_camera_nodelet.h index 645c2433e0..df105b6fbf 100644 --- a/camera/src/realsense_camera_nodelet.h +++ b/camera/src/realsense_camera_nodelet.h @@ -165,11 +165,11 @@ class RealsenseNodelet: public nodelet::Nodelet boost::shared_ptr> dynamic_reconf_server_; // Member Functions. - void enable_color_stream(); - void enable_depth_stream(); - void enable_infrared_stream(); - void enable_infrared2_stream(); - void check_error(); + void enableColorStream(); + void enableDepthStream(); + void enableInfraredStream(); + void enableInfrared2Stream(); + void checkError(); void fetchCalibData(); void prepareStreamCalibData(rs_stream calib_data); void prepareStreamData(rs_stream rs_strm); diff --git a/camera/test/realsense_camera_test_node.cpp b/camera/test/realsense_camera_test_node.cpp index 7938aca0f5..9e92b11a80 100644 --- a/camera/test/realsense_camera_test_node.cpp +++ b/camera/test/realsense_camera_test_node.cpp @@ -305,10 +305,14 @@ TEST (RealsenseTests, testIsDepthStreamEnabled) if (enable_depth) { EXPECT_TRUE (depth_recv); + EXPECT_TRUE (infrared1_recv); + EXPECT_TRUE (infrared2_recv); } else { EXPECT_FALSE (depth_recv); + EXPECT_FALSE (infrared1_recv); + EXPECT_FALSE (infrared2_recv); } } @@ -382,7 +386,7 @@ TEST (RealsenseTests, testDepthCameraInfo) TEST (RealsenseTests, testInfrared1Stream) { - if (enable_infrared1) + if (enable_depth) { EXPECT_TRUE (infrared1_avg > 0); EXPECT_TRUE (infrared1_recv); @@ -403,7 +407,7 @@ TEST (RealsenseTests, testInfrared1Stream) TEST (RealsenseTests, testInfrared1Resolution) { - if (enable_infrared1) + if (enable_depth) { if (depth_width_exp > 0) { @@ -418,7 +422,7 @@ TEST (RealsenseTests, testInfrared1Resolution) TEST (RealsenseTests, testInfrared1CameraInfo) { - if (enable_infrared1) + if (enable_depth) { EXPECT_EQ (infrared1_width_recv, inf1_caminfo_width_recv); EXPECT_EQ (infrared1_height_recv, inf1_caminfo_height_recv); @@ -449,7 +453,7 @@ TEST (RealsenseTests, testInfrared1CameraInfo) TEST (RealsenseTests, testInfrared2Stream) { - if (enable_infrared2) + if (enable_depth) { EXPECT_TRUE (infrared2_avg > 0); EXPECT_TRUE (infrared2_recv); @@ -462,7 +466,7 @@ TEST (RealsenseTests, testInfrared2Stream) TEST (RealsenseTests, testInfrared2Resolution) { - if (enable_infrared2) + if (enable_depth) { if (depth_width_exp > 0) { @@ -477,7 +481,7 @@ TEST (RealsenseTests, testInfrared2Resolution) TEST (RealsenseTests, testInfrared2CameraInfo) { - if (enable_infrared2) + if (enable_depth) { EXPECT_EQ (infrared2_width_recv, inf2_caminfo_width_recv); EXPECT_EQ (infrared2_height_recv, inf2_caminfo_height_recv); From b68dd8856bbea815a8a329b18bf506b3e0fb46be Mon Sep 17 00:00:00 2001 From: Rajvi Jingar Date: Mon, 14 Mar 2016 17:07:03 -0500 Subject: [PATCH 069/124] Update realsense_camera_test_node.h removed enable_infrared1 and enable_infrared2 flags --- camera/test/realsense_camera_test_node.h | 2 -- 1 file changed, 2 deletions(-) diff --git a/camera/test/realsense_camera_test_node.h b/camera/test/realsense_camera_test_node.h index 395f196d34..df3cc4049a 100644 --- a/camera/test/realsense_camera_test_node.h +++ b/camera/test/realsense_camera_test_node.h @@ -80,8 +80,6 @@ uint32_t infrared2_step_exp; // Expected infrared2 step. bool enable_color = true; bool enable_depth = true; -bool enable_infrared1 = true; -bool enable_infrared2 = true; bool enable_pointcloud = true; std::string depth_encoding_exp; // Expected depth encoding. From 444fe4c64dc0c26e243a4b55a214a1c4459c2608 Mon Sep 17 00:00:00 2001 From: Rajvi Jingar Date: Tue, 15 Mar 2016 14:31:55 -0500 Subject: [PATCH 070/124] Update camera_params.cfg --- camera/cfg/camera_params.cfg | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/camera/cfg/camera_params.cfg b/camera/cfg/camera_params.cfg index 9d60718b21..0dca975f71 100755 --- a/camera/cfg/camera_params.cfg +++ b/camera/cfg/camera_params.cfg @@ -7,7 +7,7 @@ from dynamic_reconfigure.parameter_generator_catkin import * gen = ParameterGenerator() # Name Type Level Description Default Min Max -gen.add("ENABLE_DEPTH", bool_t, 0, "Enable Depth", True) +gen.add("ENABLE_DEPTH", bool_t, 0, "Enable Depth", True) gen.add("COLOR_BACKLIGHT_COMPENSATION", int_t, 0, "Backlight Compensation", 1, 0, 4) gen.add("COLOR_BRIGHTNESS", int_t, 0, "Brightness", 56, 0, 255) gen.add("COLOR_CONTRAST", int_t, 0, "Contrast", 32, 16, 64) From 627296d669175c9060545c19a1777be4f2c806f5 Mon Sep 17 00:00:00 2001 From: rjingar Date: Tue, 15 Mar 2016 12:55:10 -0700 Subject: [PATCH 071/124] Fixec cfg formatting --- camera/cfg/camera_params.cfg | 40 ++++++++++++++++++------------------ 1 file changed, 20 insertions(+), 20 deletions(-) diff --git a/camera/cfg/camera_params.cfg b/camera/cfg/camera_params.cfg index 0dca975f71..abebab2fe0 100755 --- a/camera/cfg/camera_params.cfg +++ b/camera/cfg/camera_params.cfg @@ -7,25 +7,25 @@ from dynamic_reconfigure.parameter_generator_catkin import * gen = ParameterGenerator() # Name Type Level Description Default Min Max -gen.add("ENABLE_DEPTH", bool_t, 0, "Enable Depth", True) -gen.add("COLOR_BACKLIGHT_COMPENSATION", int_t, 0, "Backlight Compensation", 1, 0, 4) -gen.add("COLOR_BRIGHTNESS", int_t, 0, "Brightness", 56, 0, 255) -gen.add("COLOR_CONTRAST", int_t, 0, "Contrast", 32, 16, 64) -gen.add("COLOR_GAIN", int_t, 0, "Gain", 32, 0, 256) -gen.add("COLOR_GAMMA", int_t, 0, "Gamma", 220, 100, 280) -gen.add("COLOR_HUE", int_t, 0, "Hue", 0, -2200, 2200) -gen.add("COLOR_SATURATION", int_t, 0, "Saturation", 128, 0, 255) -gen.add("COLOR_SHARPNESS", int_t, 0, "Sharpness", 0, 0, 7) -gen.add("COLOR_WHITE_BALANCE", int_t, 0, "White Balance", 6500, 2000, 8000) -gen.add("COLOR_ENABLE_AUTO_WHITE_BALANCE", int_t, 0, "Enable Auto White Balance", 1, 0, 1) -gen.add("R200_LR_AUTO_EXPOSURE_ENABLED", int_t, 0, "LR Auto Exposure Enabled", 0, 0, 1) -gen.add("R200_LR_GAIN", int_t, 0, "LR Gain", 400, 100, 6399) -gen.add("R200_LR_EXPOSURE", int_t, 0, "LR Exposure", 164, 1, 164) -gen.add("R200_EMITTER_ENABLED", int_t, 0, "Emitter Enabled", 1, 0, 1) -gen.add("R200_DISPARITY_MULTIPLIER", int_t, 0, "Disparity Multiplier", 32, 1, 1000) -gen.add("R200_AUTO_EXPOSURE_TOP_EDGE", int_t, 0, "Auto Exposure Top Edge", 0, 0, 479) -gen.add("R200_AUTO_EXPOSURE_BOTTOM_EDGE", int_t, 0, "Auto Exposure Bottom Edge", 479, 0, 479) -gen.add("R200_AUTO_EXPOSURE_LEFT_EDGE", int_t, 0, "Auto Exposure Left Edge", 0, 0, 639) -gen.add("R200_AUTO_EXPOSURE_RIGHT_EDGE", int_t, 0, "Auto Exposure Right Edge", 639, 0, 639) +gen.add("ENABLE_DEPTH", bool_t, 0, "Enable Depth", True) +gen.add("COLOR_BACKLIGHT_COMPENSATION", int_t, 0, "Backlight Compensation", 1, 0, 4) +gen.add("COLOR_BRIGHTNESS", int_t, 0, "Brightness", 56, 0, 255) +gen.add("COLOR_CONTRAST", int_t, 0, "Contrast", 32, 16, 64) +gen.add("COLOR_GAIN", int_t, 0, "Gain", 32, 0, 256) +gen.add("COLOR_GAMMA", int_t, 0, "Gamma", 220, 100, 280) +gen.add("COLOR_HUE", int_t, 0, "Hue", 0, -2200, 2200) +gen.add("COLOR_SATURATION", int_t, 0, "Saturation", 128, 0, 255) +gen.add("COLOR_SHARPNESS", int_t, 0, "Sharpness", 0, 0, 7) +gen.add("COLOR_WHITE_BALANCE", int_t, 0, "White Balance", 6500, 2000, 8000) +gen.add("COLOR_ENABLE_AUTO_WHITE_BALANCE", int_t, 0, "Enable Auto White Balance", 1, 0, 1) +gen.add("R200_LR_AUTO_EXPOSURE_ENABLED", int_t, 0, "LR Auto Exposure Enabled", 0, 0, 1) +gen.add("R200_LR_GAIN", int_t, 0, "LR Gain", 400, 100, 6399) +gen.add("R200_LR_EXPOSURE", int_t, 0, "LR Exposure", 164, 1, 164) +gen.add("R200_EMITTER_ENABLED", int_t, 0, "Emitter Enabled", 1, 0, 1) +gen.add("R200_DISPARITY_MULTIPLIER", int_t, 0, "Disparity Multiplier", 32, 1, 1000) +gen.add("R200_AUTO_EXPOSURE_TOP_EDGE", int_t, 0, "Auto Exposure Top Edge", 0, 0, 479) +gen.add("R200_AUTO_EXPOSURE_BOTTOM_EDGE", int_t, 0, "Auto Exposure Bottom Edge", 479, 0, 479) +gen.add("R200_AUTO_EXPOSURE_LEFT_EDGE", int_t, 0, "Auto Exposure Left Edge", 0, 0, 639) +gen.add("R200_AUTO_EXPOSURE_RIGHT_EDGE", int_t, 0, "Auto Exposure Right Edge", 639, 0, 639) exit(gen.generate(PACKAGE, "realsense_camera", "camera_params")) From 233190fec2d52d2d1ccaa82a1bbd1e092fa2d21f Mon Sep 17 00:00:00 2001 From: rjingar Date: Tue, 15 Mar 2016 13:06:50 -0700 Subject: [PATCH 072/124] Fixed testfile testcase duplication after merge --- camera/test/realsense_camera_test_node.cpp | 16 ---------------- 1 file changed, 16 deletions(-) diff --git a/camera/test/realsense_camera_test_node.cpp b/camera/test/realsense_camera_test_node.cpp index 0695ba7ca5..9e92b11a80 100644 --- a/camera/test/realsense_camera_test_node.cpp +++ b/camera/test/realsense_camera_test_node.cpp @@ -316,22 +316,6 @@ TEST (RealsenseTests, testIsDepthStreamEnabled) } } -TEST (RealsenseTests, testIsDepthStreamEnabled) -{ - if (enable_depth) - { - EXPECT_TRUE (depth_recv); - EXPECT_TRUE (infrared1_recv); - EXPECT_TRUE (infrared2_recv); - } - else - { - EXPECT_FALSE (depth_recv); - EXPECT_FALSE (infrared1_recv); - EXPECT_FALSE (infrared2_recv); - } -} - TEST (RealsenseTests, testDepthStream) { if (enable_depth) From f1a0dca1a69919aa96bcbcec245c68f939f17029 Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Wed, 16 Mar 2016 15:07:09 -0700 Subject: [PATCH 073/124] RAR-256 code changes. color only unit tests fail because of RAR-332. --- camera/README.md | 93 +++--- .../realsense_r200_nodelet.launch.xml | 14 +- .../launch/realsense_r200_navigation.launch | 18 +- ...ense_r200_nodelet_standalone_manual.launch | 29 +- ...ense_r200_nodelet_standalone_preset.launch | 18 +- camera/src/realsense_camera_nodelet.cpp | 301 +++++++----------- camera/src/realsense_camera_nodelet.h | 11 +- camera/test/realsense_camera_test_node.cpp | 6 +- ..._r200_dynamic_camera_options_params.launch | 72 +++++ ...e_r200_static_camera_options_params.launch | 49 +++ ...ealsense_r200_stream_options_params.launch | 43 +++ 11 files changed, 375 insertions(+), 279 deletions(-) create mode 100644 camera/test/realsense_r200_dynamic_camera_options_params.launch create mode 100644 camera/test/realsense_r200_static_camera_options_params.launch create mode 100644 camera/test/realsense_r200_stream_options_params.launch diff --git a/camera/README.md b/camera/README.md index f804bfd891..888fc740fd 100644 --- a/camera/README.md +++ b/camera/README.md @@ -70,35 +70,36 @@ Infrared2 camera rosrun tf tf_monitor -#### Static Parameters - - mode (string, default: preset) - Specify the mode to start camera streams. Mode comprises of height, width and fps. - Preset mode enables default values whereas Manual mode enables the specified parameter values. - color_height (int, default: 480) - Specify the color camera height resolution. - color_width (int, default: 640) - Specify the color camera width resolution. - depth_height (int, default: 360) - Specify the depth camera height resolution. - depth_width (int, default: 480) - Specify the depth camera width resolution. - depth_fps (int, default: 60) - Specify the color camera FPS - depth_fps (int, default: 60) - Specify the depth camera FPS - enable_depth (bool, default: true) - Specify if to enable or not the depth and infrared camera. - enable_color (bool, default: true) - Specify if to enable or not the color camera. - enable_pointcloud (bool, default: true) - Specify if to enable or not the point cloud camera. - enable_tf (bool, default: true) - Specify if to enable or not the transform frames. - camera (string, default: "R200") - Specify the camera name. - Supported options: Following are the options supported by the R200 camera: - R200_DEPTH_CONTROL_PRESET : [0, 5] +#### Static Options + + Stream options: + mode (string, default: preset) + Specify the mode to start camera streams. Mode comprises of height, width and fps. + Preset mode enables default values whereas Manual mode enables the specified parameter values. + color_height (int, default: 480) + Specify the color camera height resolution. + color_width (int, default: 640) + Specify the color camera width resolution. + depth_height (int, default: 360) + Specify the depth camera height resolution. + depth_width (int, default: 480) + Specify the depth camera width resolution. + depth_fps (int, default: 60) + Specify the color camera FPS + depth_fps (int, default: 60) + Specify the depth camera FPS + enable_depth (bool, default: true) + Specify if to enable or not the depth and infrared camera. + enable_color (bool, default: true) + Specify if to enable or not the color camera. + enable_pointcloud (bool, default: true) + Specify if to enable or not the point cloud camera. + enable_tf (bool, default: true) + Specify if to enable or not the transform frames. + camera (string, default: "R200") + Specify the camera name. + Camera options: + Following are the options that can be set statically in the R200 camera: R200_DEPTH_UNITS : [1, 2147483647] R200_DEPTH_CLAMP_MIN : [0, 65535] R200_DEPTH_CLAMP_MAX : [0, 65535] @@ -118,9 +119,10 @@ Infrared2 camera To get supported camera options with current value set. It returns string in options:value format where different options are seperated by semicolon. -####Dynamic Parameters - List of dynamically configurable camera options: +####Dynamic Options + Camera Options: + Following are the options that can be set dynamically as well as statically in the R200 camera. COLOR_BACKLIGHT_COMPENSATION COLOR_BRIGHTNESS COLOR_CONTRAST @@ -129,41 +131,36 @@ To get supported camera options with current value set. It returns string in opt COLOR_HUE COLOR_SATURATION COLOR_SHARPNESS - COLOR_WHITE_BALANCE COLOR_ENABLE_AUTO_WHITE_BALANCE - R200_LR_AUTO_EXPOSURE_ENABLED + COLOR_WHITE_BALANCE (Must be set only if COLOR_ENABLE_AUTO_WHITE_BALANCE is disabled) R200_LR_GAIN - R200_LR_EXPOSURE R200_EMITTER_ENABLED - R200_DISPARITY_MULTIPLIER - R200_AUTO_EXPOSURE_TOP_EDGE - R200_AUTO_EXPOSURE_BOTTOM_EDGE - R200_AUTO_EXPOSURE_LEFT_EDGE - R200_AUTO_EXPOSURE_RIGHT_EDGE + R200_LR_EXPOSURE (Must be set only if R200_LR_AUTO_EXPOSURE_ENABLED is disabled) + Following are the options that can only be set dynamically in the R200 camera. + R200_LR_AUTO_EXPOSURE_ENABLED + R200_AUTO_EXPOSURE_TOP_EDGE (Must be set only if R200_LR_AUTO_EXPOSURE_ENABLED is enabled) + R200_AUTO_EXPOSURE_BOTTOM_EDGE (Must be set only if R200_LR_AUTO_EXPOSURE_ENABLED is enabled) + R200_AUTO_EXPOSURE_LEFT_EDGE (Must be set only if R200_LR_AUTO_EXPOSURE_ENABLED is enabled) + R200_AUTO_EXPOSURE_RIGHT_EDGE (Must be set only if R200_LR_AUTO_EXPOSURE_ENABLED is enabled) Enable/Disable Stream: ENABLE_DEPTH Check or uncheck the option to disable/enable depth and infrared streams dynamically. Note: Infrared streams will be enabled or disabled along with depth stream. -Use rqt_reconfigure GUI to view and edit the parameters that are accessible via dynamic_reconfigure. +Note: For Autoexposure EDGE parameters, max value will go only upto the bounds of the infrared image. +E.g. For 320x240 infrared image, valid values are within 0-319 and 0-239) +Use rqt_reconfigure GUI to view and edit the parameters that are accessible via dynamic_reconfigure. Command to launch GUI: $ rosrun rqt_reconfigure rqt_reconfigure -Change options commandline using following command: +Command to change dynamic options using commandline: $ rosrun dynamic_reconfigure dynparam set / E.g. $ rosrun dynamic_reconfigure dynparam set /RealsenseNodelet COLOR_BACKLIGHT_COMPENSATION 2 -Note: For Autoexposure EDGE parameters, max value will go only upto the bounds of the infrared image. -E.g. For 320x240 infrared image, valid values are within 0-319 and 0-239) - -To change EDGE parameters, R200_LR_AUTO_EXPOSURE_ENABLED should be enabled. -To set R200_LR_EXPOSURE, R200_LR_AUTO_EXPOSURE_ENABLED should be disabled. -To set COLOR_WHITE_BALANCE, COLOR_ENABLE_AUTO_WHITE_BALANCE should be disabled. - ###Running the R200 nodelet diff --git a/camera/launch/includes/realsense_r200_nodelet.launch.xml b/camera/launch/includes/realsense_r200_nodelet.launch.xml index 2fac0ac011..18a23db5ed 100644 --- a/camera/launch/includes/realsense_r200_nodelet.launch.xml +++ b/camera/launch/includes/realsense_r200_nodelet.launch.xml @@ -28,13 +28,13 @@ + args="load realsense_camera/RealsenseNodelet $(arg manager)"> + + + + + + diff --git a/camera/launch/realsense_r200_navigation.launch b/camera/launch/realsense_r200_navigation.launch index f32469053d..1a4105604d 100644 --- a/camera/launch/realsense_r200_navigation.launch +++ b/camera/launch/realsense_r200_navigation.launch @@ -8,13 +8,13 @@ - - - + + + + + + + + diff --git a/camera/launch/realsense_r200_nodelet_standalone_manual.launch b/camera/launch/realsense_r200_nodelet_standalone_manual.launch index f07e0fe0a4..c4159e27dd 100644 --- a/camera/launch/realsense_r200_nodelet_standalone_manual.launch +++ b/camera/launch/realsense_r200_nodelet_standalone_manual.launch @@ -14,18 +14,19 @@ - - - + + + + + + + + + + + + + + diff --git a/camera/launch/realsense_r200_nodelet_standalone_preset.launch b/camera/launch/realsense_r200_nodelet_standalone_preset.launch index f39e99e09c..dd3d1a09c0 100644 --- a/camera/launch/realsense_r200_nodelet_standalone_preset.launch +++ b/camera/launch/realsense_r200_nodelet_standalone_preset.launch @@ -8,13 +8,13 @@ - - - + + + + + + + + diff --git a/camera/src/realsense_camera_nodelet.cpp b/camera/src/realsense_camera_nodelet.cpp index 42a30da328..45033e681d 100644 --- a/camera/src/realsense_camera_nodelet.cpp +++ b/camera/src/realsense_camera_nodelet.cpp @@ -73,22 +73,8 @@ namespace realsense_camera ROS_INFO_STREAM ("RealSense Camera - Starting camera nodelet."); // Set default configurations. - depth_height_ = DEPTH_HEIGHT; - depth_width_ = DEPTH_WIDTH; - color_height_ = COLOR_HEIGHT; - color_width_ = COLOR_WIDTH; - depth_fps_ = DEPTH_FPS; - color_fps_ = COLOR_FPS; - enable_depth_ = ENABLE_DEPTH; - enable_color_ = ENABLE_COLOR; - enable_pointcloud_ = ENABLE_PC; - enable_tf_ = ENABLE_TF; is_device_started_ = false; - camera_configuration_ = getMyArgv (); - - frame_id_[RS_STREAM_DEPTH] = DEPTH_OPTICAL_DEF_FRAME; - frame_id_[RS_STREAM_COLOR] = COLOR_OPTICAL_DEF_FRAME; frame_id_[RS_STREAM_INFRARED] = IR1_DEF_FRAME; frame_id_[RS_STREAM_INFRARED2] = IR2_DEF_FRAME; @@ -96,12 +82,12 @@ namespace realsense_camera camera_info_[i] = NULL; ros::NodeHandle & nh = getNodeHandle (); + pnh_ = getPrivateNodeHandle(); // Set up the topics. image_transport::ImageTransport it (nh); - // Parse parameters. - getConfigValues (camera_configuration_); + setStreamOptions(); // Advertise the various topics and services. // Advertise color stream only if color parameter is set. @@ -117,7 +103,7 @@ namespace realsense_camera pointcloud_publisher_ = nh.advertise < sensor_msgs::PointCloud2 > (PC_TOPIC, 1); - get_options_service_ = nh.advertiseService (SETTINGS_SERVICE, &RealsenseNodelet::getCameraSettings, this); + get_options_service_ = nh.advertiseService (SETTINGS_SERVICE, &RealsenseNodelet::getCameraOptionValues, this); dynamic_reconf_server_.reset(new dynamic_reconfigure::Server(getPrivateNodeHandle())); @@ -149,7 +135,7 @@ namespace realsense_camera /* *Private Methods. */ - void RealsenseNodelet::enableColorStream() + void RealsenseNodelet::enableColorStream() { // Enable streams. if (mode_.compare ("manual") == 0) @@ -170,7 +156,7 @@ namespace realsense_camera } } - void RealsenseNodelet::enableDepthStream() + void RealsenseNodelet::enableDepthStream() { // Enable streams. if (mode_.compare ("manual") == 0) @@ -186,13 +172,13 @@ namespace realsense_camera } uint32_t stream_index = (uint32_t) RS_STREAM_DEPTH; - if(camera_info_[stream_index] == NULL) + if(camera_info_[stream_index] == NULL) { prepareStreamCalibData (RS_STREAM_DEPTH); } } - void RealsenseNodelet::enableInfraredStream() + void RealsenseNodelet::enableInfraredStream() { // Enable streams. if (mode_.compare ("manual") == 0) @@ -208,13 +194,13 @@ namespace realsense_camera } uint32_t stream_index = (uint32_t) RS_STREAM_INFRARED; - if(camera_info_[stream_index] == NULL) + if(camera_info_[stream_index] == NULL) { prepareStreamCalibData (RS_STREAM_INFRARED); } } - void RealsenseNodelet::enableInfrared2Stream() + void RealsenseNodelet::enableInfrared2Stream() { // Enable streams. if (mode_.compare ("manual") == 0) @@ -229,7 +215,7 @@ namespace realsense_camera } uint32_t stream_index = (uint32_t) RS_STREAM_INFRARED2; - if(camera_info_[stream_index] == NULL) + if(camera_info_[stream_index] == NULL) { prepareStreamCalibData (RS_STREAM_INFRARED2); } @@ -286,19 +272,19 @@ namespace realsense_camera rs_set_device_options(rs_device_, edge_options_, 4, edge_values_, 0); } - if(config.ENABLE_DEPTH == false) + if(config.ENABLE_DEPTH == false) { - if(enable_color_ == false) + if(enable_color_ == false) { ROS_INFO_STREAM ("RealSense Camera - Color stream is also disabled. Cannot disable depth stream"); config.ENABLE_DEPTH = true; } - else + else { enable_depth_ = false; } } - else + else { enable_depth_ = true; } @@ -392,7 +378,8 @@ namespace realsense_camera options.push_back (o); } - setConfigValues (camera_configuration_, options); + getCameraOptions(); + setStaticCameraOptions(); // Start device. rs_start_device (rs_device_, &rs_error_); @@ -405,6 +392,28 @@ namespace realsense_camera return true; } + /* + * Gets the options supported by the camera along with their min, max and step values. + */ + void RealsenseNodelet::getCameraOptions() + { + for (int i = 0; i < RS_OPTION_COUNT; ++i) + { + option_str o = { (rs_option) i }; + + if (rs_device_supports_option(rs_device_, o.opt, &rs_error_)) + { + rs_get_device_option_range(rs_device_, o.opt, &o.min, &o.max, &o.step, 0); + // Skip the camera options where min and max values are the same. + if (o.min != o.max) + { + o.value = rs_get_device_option(rs_device_, o.opt, 0); + options.push_back(o); + } + } + } + } + /* * Define buffer for images and prepare camera info for each enabled stream. */ @@ -488,32 +497,18 @@ namespace realsense_camera } /* - * Service function to get values for supported camera settings. + * Get the latest values of the camera options. */ - bool RealsenseNodelet::getCameraSettings (realsense_camera::cameraConfiguration::Request & req, + bool RealsenseNodelet::getCameraOptionValues(realsense_camera::cameraConfiguration::Request & req, realsense_camera::cameraConfiguration::Response & res) { std::string get_options_result_str; std::string opt_name, opt_value; - for (int i = 0; i < RS_OPTION_COUNT; ++i) + for (option_str o: options) { - option_str o = - { (rs_option) i}; - if (!rs_device_supports_option (rs_device_, o.opt, 0)) - { - continue; - } - - rs_get_device_option_range (rs_device_, o.opt, &o.min, &o.max, - &o.step, 0); - if (o.min == o.max) - { - continue; - } - - o.value = rs_get_device_option (rs_device_, o.opt, 0); - opt_name = rs_option_to_string (o.opt); + opt_name = rs_option_to_string(o.opt); + o.value = rs_get_device_option(rs_device_, o.opt, 0); opt_value = boost::lexical_cast < std::string > (o.value); get_options_result_str += opt_name + ":" + opt_value + ";"; } @@ -523,143 +518,79 @@ namespace realsense_camera } /* - * Parse commandline arguments and set parameters. + * Set the stream options based on input params. */ - void RealsenseNodelet::getConfigValues (std::vector < std::string > args) + void RealsenseNodelet::setStreamOptions() { - while (args.size () > 1) - { - config_[args[0]] = args[1]; - args.erase (args.begin ()); - args.erase (args.begin ()); - } - - if (config_.find ("mode") != config_.end ()) - { - mode_ = config_.at ("mode"); - } - - if (config_.find ("enable_color") != config_.end ()) - { - if (strcmp((config_.at ("enable_color").c_str ()),"true") == 0) - { - enable_color_ = true; - } - else - { - enable_color_ = false; - } - } - - if (config_.find ("enable_depth") != config_.end ()) - { - if (strcmp((config_.at ("enable_depth").c_str ()),"true") == 0) - { - enable_depth_ = true; - } - else - { - enable_depth_ = false; - } - } - - if (config_.find ("enable_pointcloud") != config_.end ()) - { - if (strcmp((config_.at ("enable_pointcloud").c_str ()),"true") == 0) - { - enable_pointcloud_ = true; - } - else - { - enable_pointcloud_ = false; - } - } - - if (config_.find ("enable_tf") != config_.end ()) - { - if (strcmp((config_.at ("enable_tf").c_str ()),"true") == 0) - { - enable_tf_ = true; - } - else - { - enable_tf_ = false; - } - } - - if (config_.find ("camera") != config_.end ()) - { - camera_ = config_.at ("camera").c_str (); - } - - if (config_.find ("depth_frame_id") != config_.end ()) - { - frame_id_[RS_STREAM_DEPTH] = config_.at ("depth_frame_id").c_str (); - } + pnh_.param("camera", camera_, (std::string) R200); + pnh_.param("mode", mode_, DEFAULT_MODE); + pnh_.param("enable_depth", enable_depth_, ENABLE_DEPTH); + pnh_.param("enable_color", enable_color_, ENABLE_COLOR); + pnh_.param("enable_pointcloud", enable_pointcloud_, ENABLE_PC); + pnh_.param("enable_tf", enable_tf_, ENABLE_TF); + pnh_.param("depth_width", depth_width_, DEPTH_WIDTH); + pnh_.param("depth_height", depth_height_, DEPTH_HEIGHT); + pnh_.param("color_width", color_width_, COLOR_WIDTH); + pnh_.param("color_height", color_height_, COLOR_HEIGHT); + pnh_.param("depth_fps", depth_fps_, DEPTH_FPS); + pnh_.param("color_fps", color_fps_, COLOR_FPS); + pnh_.param("depth_frame_id", frame_id_[RS_STREAM_DEPTH], (std::string) DEPTH_OPTICAL_DEF_FRAME); + pnh_.param("rgb_frame_id", frame_id_[RS_STREAM_COLOR], (std::string) COLOR_OPTICAL_DEF_FRAME); + } - if (config_.find ("rgb_frame_id") != config_.end ()) - { - frame_id_[RS_STREAM_COLOR] = config_.at ("rgb_frame_id").c_str (); - } + /* + * Set the static camera options. + */ + void RealsenseNodelet::setStaticCameraOptions() + { + // Get dynamic options from the dynamic reconfigure server. + dynamic_reconf_server_->getConfigDefault(params_config_); + std::vector param_desc = params_config_.__getParamDescriptions__(); - if (mode_.compare ("manual") == 0) + // Iterate through the supported camera options + for (option_str o: options) { - if (config_.find ("color_fps") != config_.end ()) - { - color_fps_ = atoi (config_.at ("color_fps").c_str ()); - } - - if (config_.find ("depth_fps") != config_.end ()) - { - depth_fps_ = atoi (config_.at ("depth_fps").c_str ()); - } - - if (config_.find ("color_height") != config_.end ()) - { - color_height_ = atoi (config_.at ("color_height").c_str ()); - } + std::string opt_name = rs_option_to_string(o.opt); + bool found = false; - if (config_.find ("color_width") != config_.end ()) + std::vector::iterator it; + for (camera_paramsConfig::AbstractParamDescriptionConstPtr param_desc_ptr: param_desc) { - color_width_ = atoi (config_.at ("color_width").c_str ()); + if (opt_name.compare((* param_desc_ptr).name) == 0) + { + found = true; + break; + } } - - if (config_.find ("depth_height") != config_.end ()) + // Skip the dynamic options and set only the static camera options. + if (found == false) { - depth_height_ = atoi (config_.at ("depth_height").c_str ()); - } + std::string key; + double val; - if (config_.find ("depth_width") != config_.end ()) - { - depth_width_ = atoi (config_.at ("depth_width").c_str ()); - } - } - } - - /* - * Change camera settings. - */ - void RealsenseNodelet::setConfigValues (std::vector < std::string > args, - std::vector < option_str > cam_options) - { - while (args.size () > 1) - { - config_[args[0]] = args[1]; - args.erase (args.begin ()); - args.erase (args.begin ()); - } + if (pnh_.searchParam(opt_name, key)) + { + double opt_val; + pnh_.getParam(key, val); - while (!cam_options.empty ()) - { - option_str o = cam_options.back (); - std::string opt_name = rs_option_to_string (o.opt); - if (config_.find (opt_name) != config_.end () && rs_device_supports_option (rs_device_, o.opt, 0)) - { - ROS_INFO_STREAM ("RealSense Camera - Setting" << opt_name.c_str () << " to " << config_.at (opt_name).c_str ()); - rs_set_device_option (rs_device_, o.opt, atoi (config_.at (opt_name).c_str ()), &rs_error_); - checkError (); + // Validate and set the input values within the min-max range + if (val < o.min) + { + opt_val = o.min; + } + else if (val > o.max) + { + opt_val = o.max; + } + else + { + opt_val = val; + } + ROS_INFO_STREAM ("RealSense Camera - Static Options: " << opt_name << " = " << opt_val); + rs_set_device_option (rs_device_, o.opt, opt_val, &rs_error_); + checkError(); + } } - cam_options.pop_back (); } } @@ -711,9 +642,9 @@ namespace realsense_camera */ void RealsenseNodelet::publishStreams () { - if(enable_depth_ == false && rs_is_stream_enabled (rs_device_, RS_STREAM_DEPTH, 0) == 1) + if(enable_depth_ == false && rs_is_stream_enabled (rs_device_, RS_STREAM_DEPTH, 0) == 1) { - if(rs_is_device_streaming(rs_device_, 0) == 1) + if(rs_is_device_streaming(rs_device_, 0) == 1) { rs_stop_device (rs_device_, &rs_error_); checkError (); ROS_INFO_STREAM ("RealSense Camera - Device Stopped"); @@ -729,33 +660,33 @@ namespace realsense_camera rs_disable_stream(rs_device_, RS_STREAM_INFRARED2, &rs_error_); checkError (); ROS_INFO_STREAM ("RealSense Camera - Infrared2 stream Disabled"); - if(rs_is_device_streaming(rs_device_, 0) == 0) + if(rs_is_device_streaming(rs_device_, 0) == 0) { rs_start_device (rs_device_, &rs_error_);checkError (); ROS_INFO_STREAM ("RealSense Camera - Device Started"); } - } - - if(enable_depth_ == true && rs_is_stream_enabled (rs_device_, RS_STREAM_DEPTH, 0) == 0) + } + + if(enable_depth_ == true && rs_is_stream_enabled (rs_device_, RS_STREAM_DEPTH, 0) == 0) { - if(rs_is_device_streaming(rs_device_, 0) == 1) + if(rs_is_device_streaming(rs_device_, 0) == 1) { rs_stop_device (rs_device_, &rs_error_); checkError (); ROS_INFO_STREAM ("RealSense Camera - Device Stopped"); } - + enableDepthStream(); enableInfraredStream(); enableInfrared2Stream(); - - if(rs_is_device_streaming(rs_device_, 0) == 0) + + if(rs_is_device_streaming(rs_device_, 0) == 0) { rs_start_device (rs_device_, &rs_error_); checkError (); ROS_INFO_STREAM ("RealSense Camera - Device Started"); } } - if(rs_is_device_streaming(rs_device_, 0) == 1) + if(rs_is_device_streaming(rs_device_, 0) == 1) { rs_wait_for_frames (rs_device_, &rs_error_); checkError (); @@ -764,7 +695,7 @@ namespace realsense_camera for (int stream_index = 0; stream_index < STREAM_COUNT; ++stream_index) { // Publish image stream only if there is at least one subscriber. - if (camera_publisher_[stream_index].getNumSubscribers () > 0 && + if (camera_publisher_[stream_index].getNumSubscribers () > 0 && rs_is_stream_enabled (rs_device_, (rs_stream) stream_index, 0) == 1) { prepareStreamData ((rs_stream) stream_index); diff --git a/camera/src/realsense_camera_nodelet.h b/camera/src/realsense_camera_nodelet.h index df105b6fbf..9a9ee727a0 100644 --- a/camera/src/realsense_camera_nodelet.h +++ b/camera/src/realsense_camera_nodelet.h @@ -77,6 +77,7 @@ class RealsenseNodelet: public nodelet::Nodelet // Default Constants. const int MAX_Z = 8; // in meters const int DEFAULT_CAMERA = 0; // default camera index + const std::string DEFAULT_MODE = "preset"; const int DEPTH_HEIGHT = 360; const int DEPTH_WIDTH = 480; const int COLOR_HEIGHT = 480; @@ -128,7 +129,6 @@ class RealsenseNodelet: public nodelet::Nodelet bool enable_depth_; bool enable_pointcloud_; bool enable_tf_; - std::vector camera_configuration_; std::string camera_ = "R200"; const uint16_t *image_depth16_; @@ -149,12 +149,14 @@ class RealsenseNodelet: public nodelet::Nodelet ros::Time time_stamp_; ros::Publisher pointcloud_publisher_; ros::ServiceServer get_options_service_; + ros::NodeHandle pnh_; std::string frame_id_[STREAM_COUNT]; std::string stream_encoding_[STREAM_COUNT]; std::string mode_; std::map config_; int stream_step_[STREAM_COUNT]; + camera_paramsConfig params_config_; struct option_str { @@ -177,12 +179,13 @@ class RealsenseNodelet: public nodelet::Nodelet void publishPointCloud(cv::Mat & image_rgb); void publishTransforms(); void devicePoll(); + void getCameraOptions(); void allocateResources(); bool connectToCamera(); void fillStreamEncoding(); - void getConfigValues(std::vector args); - void setConfigValues(std::vector args, std::vector cam_options); - bool getCameraSettings(realsense_camera::cameraConfiguration::Request & req, realsense_camera::cameraConfiguration::Response & res); + void setStreamOptions(); + void setStaticCameraOptions(); + bool getCameraOptionValues(realsense_camera::cameraConfiguration::Request & req, realsense_camera::cameraConfiguration::Response & res); void configCallback(realsense_camera::camera_paramsConfig &config, uint32_t level); }; diff --git a/camera/test/realsense_camera_test_node.cpp b/camera/test/realsense_camera_test_node.cpp index 9e92b11a80..ef1dafdbc9 100644 --- a/camera/test/realsense_camera_test_node.cpp +++ b/camera/test/realsense_camera_test_node.cpp @@ -525,7 +525,7 @@ TEST (RealsenseTests, testInfrared2CameraInfo) } } - +/* TEST (RealsenseTests, testCameraSettings) { stringstream ss (srv.response.configuration_str); @@ -545,7 +545,7 @@ TEST (RealsenseTests, testCameraSettings) } } } - +*/ TEST (RealsenseTests, testTransforms) { // make sure all transforms are being broadcast as expected @@ -558,7 +558,7 @@ TEST (RealsenseTests, testTransforms) EXPECT_TRUE(tf_listener.canTransform (COLOR_DEF_FRAME,COLOR_OPTICAL_DEF_FRAME, ros::Time::now())); } -TEST (RealsenseTests, testDynamicReconfigure) +TEST (RealsenseTests, testCameraOptions) { stringstream settings_ss (srv.response.configuration_str); string setting; diff --git a/camera/test/realsense_r200_dynamic_camera_options_params.launch b/camera/test/realsense_r200_dynamic_camera_options_params.launch new file mode 100644 index 0000000000..b57837cd3a --- /dev/null +++ b/camera/test/realsense_r200_dynamic_camera_options_params.launch @@ -0,0 +1,72 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/camera/test/realsense_r200_static_camera_options_params.launch b/camera/test/realsense_r200_static_camera_options_params.launch new file mode 100644 index 0000000000..9ae48c0b6d --- /dev/null +++ b/camera/test/realsense_r200_static_camera_options_params.launch @@ -0,0 +1,49 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/camera/test/realsense_r200_stream_options_params.launch b/camera/test/realsense_r200_stream_options_params.launch new file mode 100644 index 0000000000..5bd281403b --- /dev/null +++ b/camera/test/realsense_r200_stream_options_params.launch @@ -0,0 +1,43 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + From 6298a577cdaa85f153f5758c5ddb0646ad02e6a3 Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Wed, 16 Mar 2016 15:20:24 -0700 Subject: [PATCH 074/124] RAR-325 rgbd launch file changes. --- .../includes/realsense_r200_nodelet.launch.xml | 13 +++++-------- camera/launch/realsense_r200_rgbd.launch | 6 ++---- 2 files changed, 7 insertions(+), 12 deletions(-) diff --git a/camera/launch/includes/realsense_r200_nodelet.launch.xml b/camera/launch/includes/realsense_r200_nodelet.launch.xml index 18a23db5ed..361fe6ed63 100644 --- a/camera/launch/includes/realsense_r200_nodelet.launch.xml +++ b/camera/launch/includes/realsense_r200_nodelet.launch.xml @@ -4,11 +4,12 @@ - + + @@ -16,12 +17,7 @@ - - - - - + @@ -29,10 +25,11 @@ + - + diff --git a/camera/launch/realsense_r200_rgbd.launch b/camera/launch/realsense_r200_rgbd.launch index d0e207d34c..4a9e760ac7 100644 --- a/camera/launch/realsense_r200_rgbd.launch +++ b/camera/launch/realsense_r200_rgbd.launch @@ -17,11 +17,9 @@ - + - + From dd088a09a22b05bde7701cf42bfbe2e1ba53c040 Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Wed, 16 Mar 2016 15:33:46 -0700 Subject: [PATCH 075/124] RAR-332 quick fix. Color only unit test works now. --- camera/README.md | 12 +++++------- camera/cfg/camera_params.cfg | 2 +- camera/src/realsense_camera_nodelet.cpp | 4 ++-- 3 files changed, 8 insertions(+), 10 deletions(-) diff --git a/camera/README.md b/camera/README.md index 888fc740fd..edcf21b1f9 100644 --- a/camera/README.md +++ b/camera/README.md @@ -88,8 +88,6 @@ Infrared2 camera Specify the color camera FPS depth_fps (int, default: 60) Specify the depth camera FPS - enable_depth (bool, default: true) - Specify if to enable or not the depth and infrared camera. enable_color (bool, default: true) Specify if to enable or not the color camera. enable_pointcloud (bool, default: true) @@ -121,6 +119,11 @@ To get supported camera options with current value set. It returns string in opt ####Dynamic Options + Stream Options: + enable_depth (bool, default: true) + Specify if to enable or not the depth and infrared camera. + Note: Infrared streams will be enabled or disabled along with depth stream. + Camera Options: Following are the options that can be set dynamically as well as statically in the R200 camera. COLOR_BACKLIGHT_COMPENSATION @@ -143,11 +146,6 @@ To get supported camera options with current value set. It returns string in opt R200_AUTO_EXPOSURE_LEFT_EDGE (Must be set only if R200_LR_AUTO_EXPOSURE_ENABLED is enabled) R200_AUTO_EXPOSURE_RIGHT_EDGE (Must be set only if R200_LR_AUTO_EXPOSURE_ENABLED is enabled) - Enable/Disable Stream: - ENABLE_DEPTH - Check or uncheck the option to disable/enable depth and infrared streams dynamically. - Note: Infrared streams will be enabled or disabled along with depth stream. - Note: For Autoexposure EDGE parameters, max value will go only upto the bounds of the infrared image. E.g. For 320x240 infrared image, valid values are within 0-319 and 0-239) diff --git a/camera/cfg/camera_params.cfg b/camera/cfg/camera_params.cfg index abebab2fe0..5bc290eafb 100755 --- a/camera/cfg/camera_params.cfg +++ b/camera/cfg/camera_params.cfg @@ -7,7 +7,7 @@ from dynamic_reconfigure.parameter_generator_catkin import * gen = ParameterGenerator() # Name Type Level Description Default Min Max -gen.add("ENABLE_DEPTH", bool_t, 0, "Enable Depth", True) +gen.add("enable_depth", bool_t, 0, "Enable Depth", True) gen.add("COLOR_BACKLIGHT_COMPENSATION", int_t, 0, "Backlight Compensation", 1, 0, 4) gen.add("COLOR_BRIGHTNESS", int_t, 0, "Brightness", 56, 0, 255) gen.add("COLOR_CONTRAST", int_t, 0, "Contrast", 32, 16, 64) diff --git a/camera/src/realsense_camera_nodelet.cpp b/camera/src/realsense_camera_nodelet.cpp index 45033e681d..546a488f5d 100644 --- a/camera/src/realsense_camera_nodelet.cpp +++ b/camera/src/realsense_camera_nodelet.cpp @@ -272,12 +272,12 @@ namespace realsense_camera rs_set_device_options(rs_device_, edge_options_, 4, edge_values_, 0); } - if(config.ENABLE_DEPTH == false) + if(config.enable_depth == false) { if(enable_color_ == false) { ROS_INFO_STREAM ("RealSense Camera - Color stream is also disabled. Cannot disable depth stream"); - config.ENABLE_DEPTH = true; + config.enable_depth = true; } else { From 275b69af564564c99befa808bd6d7763152eb1b5 Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Wed, 16 Mar 2016 18:02:47 -0700 Subject: [PATCH 076/124] Updated code review comments. --- camera/README.md | 20 +++++++------- camera/src/realsense_camera_nodelet.cpp | 27 +++---------------- camera/src/realsense_camera_nodelet.h | 1 - camera/test/realsense_camera_test_node.cpp | 21 --------------- ...ealsense_r200_stream_options_params.launch | 4 +-- 5 files changed, 15 insertions(+), 58 deletions(-) diff --git a/camera/README.md b/camera/README.md index edcf21b1f9..12add2d210 100644 --- a/camera/README.md +++ b/camera/README.md @@ -70,9 +70,9 @@ Infrared2 camera rosrun tf tf_monitor -#### Static Options +#### Static Parameters - Stream options: + Stream parameters: mode (string, default: preset) Specify the mode to start camera streams. Mode comprises of height, width and fps. Preset mode enables default values whereas Manual mode enables the specified parameter values. @@ -96,8 +96,8 @@ Infrared2 camera Specify if to enable or not the transform frames. camera (string, default: "R200") Specify the camera name. - Camera options: - Following are the options that can be set statically in the R200 camera: + Camera parameters: + Following are the parameters that can be set only statically in the R200 camera: R200_DEPTH_UNITS : [1, 2147483647] R200_DEPTH_CLAMP_MIN : [0, 65535] R200_DEPTH_CLAMP_MAX : [0, 65535] @@ -117,15 +117,15 @@ Infrared2 camera To get supported camera options with current value set. It returns string in options:value format where different options are seperated by semicolon. -####Dynamic Options +####Dynamic Parameters - Stream Options: + Stream parameters: enable_depth (bool, default: true) Specify if to enable or not the depth and infrared camera. Note: Infrared streams will be enabled or disabled along with depth stream. - Camera Options: - Following are the options that can be set dynamically as well as statically in the R200 camera. + Camera parameters: + Following are the parameters that can be set dynamically as well as statically in the R200 camera. COLOR_BACKLIGHT_COMPENSATION COLOR_BRIGHTNESS COLOR_CONTRAST @@ -139,7 +139,7 @@ To get supported camera options with current value set. It returns string in opt R200_LR_GAIN R200_EMITTER_ENABLED R200_LR_EXPOSURE (Must be set only if R200_LR_AUTO_EXPOSURE_ENABLED is disabled) - Following are the options that can only be set dynamically in the R200 camera. + Following are the parameters that can only be set dynamically in the R200 camera. R200_LR_AUTO_EXPOSURE_ENABLED R200_AUTO_EXPOSURE_TOP_EDGE (Must be set only if R200_LR_AUTO_EXPOSURE_ENABLED is enabled) R200_AUTO_EXPOSURE_BOTTOM_EDGE (Must be set only if R200_LR_AUTO_EXPOSURE_ENABLED is enabled) @@ -154,7 +154,7 @@ Command to launch GUI: $ rosrun rqt_reconfigure rqt_reconfigure -Command to change dynamic options using commandline: +Command to change dynamic parameters using commandline: $ rosrun dynamic_reconfigure dynparam set / E.g. $ rosrun dynamic_reconfigure dynparam set /RealsenseNodelet COLOR_BACKLIGHT_COMPENSATION 2 diff --git a/camera/src/realsense_camera_nodelet.cpp b/camera/src/realsense_camera_nodelet.cpp index 546a488f5d..957ec46cf2 100644 --- a/camera/src/realsense_camera_nodelet.cpp +++ b/camera/src/realsense_camera_nodelet.cpp @@ -90,9 +90,7 @@ namespace realsense_camera setStreamOptions(); // Advertise the various topics and services. - // Advertise color stream only if color parameter is set. camera_publisher_[RS_STREAM_COLOR] = it.advertiseCamera (COLOR_TOPIC, 1); - // Advertise depth and infrared streams only if depth parameter is set. camera_publisher_[RS_STREAM_DEPTH] = it.advertiseCamera (DEPTH_TOPIC, 1); camera_publisher_[RS_STREAM_INFRARED] = it.advertiseCamera (IR1_TOPIC, 1); if (camera_.find (R200) != std::string::npos) @@ -358,26 +356,6 @@ namespace realsense_camera enableInfrared2Stream(); } - for (int i = 0; i < RS_OPTION_COUNT; ++i) - { - option_str o = - { (rs_option) i}; - - if (!rs_device_supports_option (rs_device_, o.opt, 0)) - { - continue; - } - - rs_get_device_option_range (rs_device_, o.opt, &o.min, &o.max, &o.step, 0); - if (o.min == o.max) - { - continue; - } - - o.value = rs_get_device_option (rs_device_, o.opt, 0); - options.push_back (o); - } - getCameraOptions(); setStaticCameraOptions(); @@ -544,8 +522,9 @@ namespace realsense_camera void RealsenseNodelet::setStaticCameraOptions() { // Get dynamic options from the dynamic reconfigure server. - dynamic_reconf_server_->getConfigDefault(params_config_); - std::vector param_desc = params_config_.__getParamDescriptions__(); + camera_paramsConfig params_config; + dynamic_reconf_server_->getConfigDefault(params_config); + std::vector param_desc = params_config.__getParamDescriptions__(); // Iterate through the supported camera options for (option_str o: options) diff --git a/camera/src/realsense_camera_nodelet.h b/camera/src/realsense_camera_nodelet.h index 9a9ee727a0..665d37a82e 100644 --- a/camera/src/realsense_camera_nodelet.h +++ b/camera/src/realsense_camera_nodelet.h @@ -156,7 +156,6 @@ class RealsenseNodelet: public nodelet::Nodelet std::string mode_; std::map config_; int stream_step_[STREAM_COUNT]; - camera_paramsConfig params_config_; struct option_str { diff --git a/camera/test/realsense_camera_test_node.cpp b/camera/test/realsense_camera_test_node.cpp index ef1dafdbc9..ed4f451586 100644 --- a/camera/test/realsense_camera_test_node.cpp +++ b/camera/test/realsense_camera_test_node.cpp @@ -525,27 +525,6 @@ TEST (RealsenseTests, testInfrared2CameraInfo) } } -/* -TEST (RealsenseTests, testCameraSettings) -{ - stringstream ss (srv.response.configuration_str); - string item; - string option_name; - - while (getline (ss, item, ';')) - { - stringstream ss1 (item); - getline (ss1, option_name, ':'); - if (config_args.find (option_name) != config_args.end ()) - { - std::string last_element (item.substr (item.rfind (":") + 1)); - int expected_value = atoi (last_element.c_str ()); - int current_Value = atoi (config_args.at (option_name).c_str ()); - EXPECT_EQ (current_Value, expected_value); - } - } -} -*/ TEST (RealsenseTests, testTransforms) { // make sure all transforms are being broadcast as expected diff --git a/camera/test/realsense_r200_stream_options_params.launch b/camera/test/realsense_r200_stream_options_params.launch index 5bd281403b..4b10abad4f 100644 --- a/camera/test/realsense_r200_stream_options_params.launch +++ b/camera/test/realsense_r200_stream_options_params.launch @@ -3,14 +3,14 @@ Steps: roslaunch realsense_camera realsense_r200_stream_options_params.launch - rosrun realsense_camera realsense_camera_test mode manual enable_depth true enable_color true enable_pointcloud true enable_tf true depth_width 320 depth_height 240 color_width 320 color_height 240 depth_fps 60 color_fps 60 camera R200 + rosrun realsense_camera realsense_camera_test mode manual enable_depth false enable_color true enable_pointcloud true enable_tf true depth_width 320 depth_height 240 color_width 320 color_height 240 depth_fps 60 color_fps 60 camera R200 Verify that all the tests pass. --> - + From 4480a6fd2608089da27604b56faf56751db9a821 Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Thu, 17 Mar 2016 17:34:46 -0700 Subject: [PATCH 077/124] Updated README to indicate changes in R200_DISPARITY_MULTIPLIER. --- camera/README.md | 1 + 1 file changed, 1 insertion(+) diff --git a/camera/README.md b/camera/README.md index 12add2d210..6c787802a2 100644 --- a/camera/README.md +++ b/camera/README.md @@ -138,6 +138,7 @@ To get supported camera options with current value set. It returns string in opt COLOR_WHITE_BALANCE (Must be set only if COLOR_ENABLE_AUTO_WHITE_BALANCE is disabled) R200_LR_GAIN R200_EMITTER_ENABLED + R200_DISPARITY_MULTIPLIER (This parameter does not work in the latest R200 firmware release. Likely to be removed in the next ros-realsense release.) R200_LR_EXPOSURE (Must be set only if R200_LR_AUTO_EXPOSURE_ENABLED is disabled) Following are the parameters that can only be set dynamically in the R200 camera. R200_LR_AUTO_EXPOSURE_ENABLED From 2eddc52a55bd8018965828d11b7f4ec2e7222a18 Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Mon, 21 Mar 2016 14:48:40 -0700 Subject: [PATCH 078/124] Added missing install targets This fixes Pull Request #2 --- camera/CMakeLists.txt | 28 +++++++++++++++---- camera/package.xml | 7 ++--- .../realsense_camera_nodelet_plugins.xml | 0 3 files changed, 26 insertions(+), 9 deletions(-) rename camera/{src => }/realsense_camera_nodelet_plugins.xml (100%) diff --git a/camera/CMakeLists.txt b/camera/CMakeLists.txt index 29dc548ee9..2625b7cb29 100644 --- a/camera/CMakeLists.txt +++ b/camera/CMakeLists.txt @@ -43,29 +43,47 @@ generate_dynamic_reconfigure_options( cfg/camera_params.cfg ) - - include_directories( ${catkin_INCLUDE_DIRS} ) add_library(realsense_camera_nodelet src/realsense_camera_nodelet.cpp) -target_link_libraries(realsense_camera_nodelet +target_link_libraries(realsense_camera_nodelet ${catkin_LIBRARIES} /usr/local/lib/librealsense.so ) add_dependencies(realsense_camera_nodelet realsense_camera_generate_messages_cpp ${PROJECT_NAME}_gencfg) add_executable(realsense_camera_test test/realsense_camera_test_node.cpp) -target_link_libraries(realsense_camera_test +target_link_libraries(realsense_camera_test ${catkin_LIBRARIES} ${GTEST_LIBRARIES} ) add_dependencies(realsense_camera_test realsense_camera_generate_messages_cpp ${PROJECT_NAME}_gencfg) add_executable(realsense_camera_test_rgbd test/realsense_camera_test_rgbd_node.cpp) -target_link_libraries(realsense_camera_test_rgbd +target_link_libraries(realsense_camera_test_rgbd ${catkin_LIBRARIES} ${GTEST_LIBRARIES} ) add_dependencies(realsense_camera_test_rgbd realsense_camera_generate_messages_cpp) + +# Install nodelet library +install(TARGETS realsense_camera_nodelet LIBRARY + DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} +) + +# Install launch files +install(DIRECTORY launch/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch +) + +# Install rviz files +install(DIRECTORY rviz/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/rviz +) + +# Install xml files +install(FILES package.xml realsense_camera_nodelet_plugins.xml + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) diff --git a/camera/package.xml b/camera/package.xml index 688fa556a6..fc8ed84653 100644 --- a/camera/package.xml +++ b/camera/package.xml @@ -11,7 +11,7 @@ http://www.ros.org/wiki/RealSense - Rajvi Jingar + Rajvi Jingar Reagan Lopez Matt Hansen @@ -28,7 +28,7 @@ rostest pcl_ros dynamic_reconfigure - + roscpp nodelet cv_bridge @@ -44,7 +44,6 @@ rgbd_launch - + - diff --git a/camera/src/realsense_camera_nodelet_plugins.xml b/camera/realsense_camera_nodelet_plugins.xml similarity index 100% rename from camera/src/realsense_camera_nodelet_plugins.xml rename to camera/realsense_camera_nodelet_plugins.xml From 86b3f67bbe592ed0bc507ab27f437ae0beede1f8 Mon Sep 17 00:00:00 2001 From: rjingar Date: Tue, 22 Mar 2016 15:01:30 -0700 Subject: [PATCH 079/124] Removed R200_DISPARITY_MULTIPLIER camera option support --- camera/README.md | 1 - camera/cfg/camera_params.cfg | 1 - camera/src/realsense_camera_nodelet.cpp | 1 - 3 files changed, 3 deletions(-) diff --git a/camera/README.md b/camera/README.md index 6c787802a2..12add2d210 100644 --- a/camera/README.md +++ b/camera/README.md @@ -138,7 +138,6 @@ To get supported camera options with current value set. It returns string in opt COLOR_WHITE_BALANCE (Must be set only if COLOR_ENABLE_AUTO_WHITE_BALANCE is disabled) R200_LR_GAIN R200_EMITTER_ENABLED - R200_DISPARITY_MULTIPLIER (This parameter does not work in the latest R200 firmware release. Likely to be removed in the next ros-realsense release.) R200_LR_EXPOSURE (Must be set only if R200_LR_AUTO_EXPOSURE_ENABLED is disabled) Following are the parameters that can only be set dynamically in the R200 camera. R200_LR_AUTO_EXPOSURE_ENABLED diff --git a/camera/cfg/camera_params.cfg b/camera/cfg/camera_params.cfg index 17cca2072d..031bf75267 100755 --- a/camera/cfg/camera_params.cfg +++ b/camera/cfg/camera_params.cfg @@ -22,7 +22,6 @@ gen.add("R200_LR_AUTO_EXPOSURE_ENABLED", int_t, 0, "LR Auto gen.add("R200_LR_GAIN", int_t, 0, "LR Gain", 400, 100, 6399) gen.add("R200_LR_EXPOSURE", int_t, 0, "LR Exposure", 164, 1, 164) gen.add("R200_EMITTER_ENABLED", int_t, 0, "Emitter Enabled", 1, 0, 1) -gen.add("R200_DISPARITY_MULTIPLIER", int_t, 0, "Disparity Multiplier", 32, 1, 1000) gen.add("R200_AUTO_EXPOSURE_TOP_EDGE", int_t, 0, "Auto Exposure Top Edge", 0, 0, 479) gen.add("R200_AUTO_EXPOSURE_BOTTOM_EDGE", int_t, 0, "Auto Exposure Bottom Edge", 479, 0, 479) gen.add("R200_AUTO_EXPOSURE_LEFT_EDGE", int_t, 0, "Auto Exposure Left Edge", 0, 0, 639) diff --git a/camera/src/realsense_camera_nodelet.cpp b/camera/src/realsense_camera_nodelet.cpp index bc16d9e8d6..c44a20174d 100644 --- a/camera/src/realsense_camera_nodelet.cpp +++ b/camera/src/realsense_camera_nodelet.cpp @@ -246,7 +246,6 @@ namespace realsense_camera rs_set_device_option(rs_device_, RS_OPTION_R200_LR_GAIN, config.R200_LR_GAIN, 0); rs_set_device_option(rs_device_, RS_OPTION_R200_EMITTER_ENABLED, config.R200_EMITTER_ENABLED, 0); - rs_set_device_option(rs_device_, RS_OPTION_R200_DISPARITY_MULTIPLIER, config.R200_DISPARITY_MULTIPLIER, 0); if(config.R200_LR_AUTO_EXPOSURE_ENABLED == 1) { From a17ca30a6b83b6c6ff525513bd6db84b1cdf68e9 Mon Sep 17 00:00:00 2001 From: rjingar Date: Wed, 23 Mar 2016 09:18:18 -0700 Subject: [PATCH 080/124] Corrected spacing and formatting --- camera/src/realsense_camera_nodelet.cpp | 289 +++++++++++++----------- 1 file changed, 157 insertions(+), 132 deletions(-) diff --git a/camera/src/realsense_camera_nodelet.cpp b/camera/src/realsense_camera_nodelet.cpp index c44a20174d..4756ce5301 100644 --- a/camera/src/realsense_camera_nodelet.cpp +++ b/camera/src/realsense_camera_nodelet.cpp @@ -44,9 +44,9 @@ namespace realsense_camera /* * Public Methods. */ - RealsenseNodelet::~RealsenseNodelet () + RealsenseNodelet::~RealsenseNodelet() { - device_thread_->join (); + device_thread_->join(); if (enable_tf_ == true) { @@ -56,19 +56,19 @@ namespace realsense_camera // Stop device. if (is_device_started_ == true) { - rs_stop_device (rs_device_, 0); - rs_delete_context (rs_context_, &rs_error_); - checkError (); + rs_stop_device(rs_device_, 0); + rs_delete_context(rs_context_, &rs_error_); + checkError(); } ROS_INFO_STREAM ("RealSense Camera - Stopping camera nodelet."); - ros::shutdown (); + ros::shutdown(); } /* * Initialize the realsense code. */ - void RealsenseNodelet::onInit () + void RealsenseNodelet::onInit() { ROS_INFO_STREAM ("RealSense Camera - Starting camera nodelet."); @@ -79,9 +79,11 @@ namespace realsense_camera frame_id_[RS_STREAM_INFRARED2] = IR2_DEF_FRAME; for (int i = 0; i < STREAM_COUNT; ++i) + { camera_info_[i] = NULL; + } - ros::NodeHandle & nh = getNodeHandle (); + ros::NodeHandle & nh = getNodeHandle(); pnh_ = getPrivateNodeHandle(); // Set up the topics. @@ -90,41 +92,41 @@ namespace realsense_camera setStreamOptions(); // Advertise the various topics and services. - camera_publisher_[RS_STREAM_COLOR] = it.advertiseCamera (COLOR_TOPIC, 1); - camera_publisher_[RS_STREAM_DEPTH] = it.advertiseCamera (DEPTH_TOPIC, 1); - camera_publisher_[RS_STREAM_INFRARED] = it.advertiseCamera (IR1_TOPIC, 1); + camera_publisher_[RS_STREAM_COLOR] = it.advertiseCamera(COLOR_TOPIC, 1); + camera_publisher_[RS_STREAM_DEPTH] = it.advertiseCamera(DEPTH_TOPIC, 1); + camera_publisher_[RS_STREAM_INFRARED] = it.advertiseCamera(IR1_TOPIC, 1); if (camera_.find (R200) != std::string::npos) { - camera_publisher_[RS_STREAM_INFRARED2] = it.advertiseCamera (IR2_TOPIC, 1); + camera_publisher_[RS_STREAM_INFRARED2] = it.advertiseCamera(IR2_TOPIC, 1); } - pointcloud_publisher_ = nh.advertise < sensor_msgs::PointCloud2 > (PC_TOPIC, 1); + pointcloud_publisher_ = nh.advertise(PC_TOPIC, 1); - get_options_service_ = nh.advertiseService (SETTINGS_SERVICE, &RealsenseNodelet::getCameraOptionValues, this); + get_options_service_ = nh.advertiseService(SETTINGS_SERVICE, &RealsenseNodelet::getCameraOptionValues, this); dynamic_reconf_server_.reset(new dynamic_reconfigure::Server(getPrivateNodeHandle())); bool connected = false; - connected = connectToCamera (); + connected = connectToCamera(); if (connected == true) { // Start working thread. device_thread_ = - boost::shared_ptr < boost::thread > (new boost::thread (boost::bind (&RealsenseNodelet::devicePoll, this))); + boost::shared_ptr (new boost::thread (boost::bind(&RealsenseNodelet::devicePoll, this))); if (enable_tf_ == true) { transform_thread_ = - boost::shared_ptr < boost::thread > (new boost::thread (boost::bind (&RealsenseNodelet::publishTransforms, this))); + boost::shared_ptr(new boost::thread (boost::bind(&RealsenseNodelet::publishTransforms, this))); } } else { - ros::shutdown (); + ros::shutdown(); } dynamic_reconf_server_->setCallback(boost::bind(&RealsenseNodelet::configCallback, this, _1, _2)); @@ -139,17 +141,19 @@ namespace realsense_camera if (mode_.compare ("manual") == 0) { ROS_INFO_STREAM ("RealSense Camera - Enabling Color Stream: manual mode"); - rs_enable_stream (rs_device_, RS_STREAM_COLOR, color_width_, color_height_, COLOR_FORMAT, color_fps_, &rs_error_); - checkError (); + rs_enable_stream(rs_device_, RS_STREAM_COLOR, color_width_, color_height_, COLOR_FORMAT, color_fps_, &rs_error_); + checkError(); } else { ROS_INFO_STREAM ("RealSense Camera - Enabling Color Stream: preset mode"); - rs_enable_stream_preset (rs_device_, RS_STREAM_COLOR, RS_PRESET_BEST_QUALITY, &rs_error_); checkError (); + rs_enable_stream_preset(rs_device_, RS_STREAM_COLOR, RS_PRESET_BEST_QUALITY, &rs_error_); + checkError(); } uint32_t stream_index = (uint32_t) RS_STREAM_COLOR; - if(camera_info_[stream_index] == NULL) { + if (camera_info_[stream_index] == NULL) + { prepareStreamCalibData (RS_STREAM_COLOR); } } @@ -160,17 +164,18 @@ namespace realsense_camera if (mode_.compare ("manual") == 0) { ROS_INFO_STREAM ("RealSense Camera - Enabling Depth Stream: manual mode"); - rs_enable_stream (rs_device_, RS_STREAM_DEPTH, depth_width_, depth_height_, DEPTH_FORMAT, depth_fps_, &rs_error_); - checkError (); + rs_enable_stream(rs_device_, RS_STREAM_DEPTH, depth_width_, depth_height_, DEPTH_FORMAT, depth_fps_, &rs_error_); + checkError(); } else { ROS_INFO_STREAM ("RealSense Camera - Enabling Depth Stream: preset mode"); - rs_enable_stream_preset (rs_device_, RS_STREAM_DEPTH, RS_PRESET_BEST_QUALITY, &rs_error_); checkError (); + rs_enable_stream_preset(rs_device_, RS_STREAM_DEPTH, RS_PRESET_BEST_QUALITY, &rs_error_); + checkError(); } uint32_t stream_index = (uint32_t) RS_STREAM_DEPTH; - if(camera_info_[stream_index] == NULL) + if (camera_info_[stream_index] == NULL) { prepareStreamCalibData (RS_STREAM_DEPTH); } @@ -182,17 +187,18 @@ namespace realsense_camera if (mode_.compare ("manual") == 0) { ROS_INFO_STREAM ("RealSense Camera - Enabling Infrared Stream: manual mode"); - rs_enable_stream (rs_device_, RS_STREAM_INFRARED, depth_width_, depth_height_, IR1_FORMAT, depth_fps_, &rs_error_); - checkError (); + rs_enable_stream(rs_device_, RS_STREAM_INFRARED, depth_width_, depth_height_, IR1_FORMAT, depth_fps_, &rs_error_); + checkError(); } else { ROS_INFO_STREAM ("RealSense Camera - Enabling Infrared Stream: preset mode"); - rs_enable_stream_preset (rs_device_, RS_STREAM_INFRARED, RS_PRESET_BEST_QUALITY, &rs_error_); checkError (); + rs_enable_stream_preset(rs_device_, RS_STREAM_INFRARED, RS_PRESET_BEST_QUALITY, &rs_error_); + checkError(); } uint32_t stream_index = (uint32_t) RS_STREAM_INFRARED; - if(camera_info_[stream_index] == NULL) + if (camera_info_[stream_index] == NULL) { prepareStreamCalibData (RS_STREAM_INFRARED); } @@ -204,16 +210,16 @@ namespace realsense_camera if (mode_.compare ("manual") == 0) { ROS_INFO_STREAM ("RealSense Camera - Enabling Infrared2 Stream: manual mode"); - rs_enable_stream (rs_device_, RS_STREAM_INFRARED2, depth_width_, depth_height_, IR2_FORMAT, depth_fps_, 0); + rs_enable_stream(rs_device_, RS_STREAM_INFRARED2, depth_width_, depth_height_, IR2_FORMAT, depth_fps_, 0); } else { ROS_INFO_STREAM ("RealSense Camera - Enabling Infrared2 Stream: preset mode"); - rs_enable_stream_preset (rs_device_, RS_STREAM_INFRARED2, RS_PRESET_BEST_QUALITY, 0); + rs_enable_stream_preset(rs_device_, RS_STREAM_INFRARED2, RS_PRESET_BEST_QUALITY, 0); } uint32_t stream_index = (uint32_t) RS_STREAM_INFRARED2; - if(camera_info_[stream_index] == NULL) + if (camera_info_[stream_index] == NULL) { prepareStreamCalibData (RS_STREAM_INFRARED2); } @@ -233,32 +239,38 @@ namespace realsense_camera rs_set_device_option(rs_device_, RS_OPTION_COLOR_SHARPNESS, config.COLOR_SHARPNESS, 0); rs_set_device_option(rs_device_, RS_OPTION_COLOR_ENABLE_AUTO_WHITE_BALANCE, config.COLOR_ENABLE_AUTO_WHITE_BALANCE, 0); - if(config.COLOR_ENABLE_AUTO_WHITE_BALANCE == 0) { + if (config.COLOR_ENABLE_AUTO_WHITE_BALANCE == 0) + { rs_set_device_option(rs_device_, RS_OPTION_COLOR_WHITE_BALANCE, config.COLOR_WHITE_BALANCE, 0); } //R200 camera specific options rs_set_device_option(rs_device_, RS_OPTION_R200_LR_AUTO_EXPOSURE_ENABLED, config.R200_LR_AUTO_EXPOSURE_ENABLED, 0); - if(config.R200_LR_AUTO_EXPOSURE_ENABLED == 0) { + if (config.R200_LR_AUTO_EXPOSURE_ENABLED == 0) + { rs_set_device_option(rs_device_, RS_OPTION_R200_LR_EXPOSURE, config.R200_LR_EXPOSURE, 0); } rs_set_device_option(rs_device_, RS_OPTION_R200_LR_GAIN, config.R200_LR_GAIN, 0); rs_set_device_option(rs_device_, RS_OPTION_R200_EMITTER_ENABLED, config.R200_EMITTER_ENABLED, 0); - if(config.R200_LR_AUTO_EXPOSURE_ENABLED == 1) + if (config.R200_LR_AUTO_EXPOSURE_ENABLED == 1) { - if(config.R200_AUTO_EXPOSURE_TOP_EDGE >= depth_height_) { + if (config.R200_AUTO_EXPOSURE_TOP_EDGE >= depth_height_) + { config.R200_AUTO_EXPOSURE_TOP_EDGE = depth_height_ - 1; } - if(config.R200_AUTO_EXPOSURE_BOTTOM_EDGE >= depth_height_) { + if (config.R200_AUTO_EXPOSURE_BOTTOM_EDGE >= depth_height_) + { config.R200_AUTO_EXPOSURE_BOTTOM_EDGE = depth_height_ - 1; } - if(config.R200_AUTO_EXPOSURE_LEFT_EDGE >= depth_width_) { + if (config.R200_AUTO_EXPOSURE_LEFT_EDGE >= depth_width_) + { config.R200_AUTO_EXPOSURE_LEFT_EDGE = depth_width_ - 1; } - if(config.R200_AUTO_EXPOSURE_RIGHT_EDGE >= depth_width_) { + if (config.R200_AUTO_EXPOSURE_RIGHT_EDGE >= depth_width_) + { config.R200_AUTO_EXPOSURE_RIGHT_EDGE = depth_width_ - 1; } edge_values_[0] = config.R200_AUTO_EXPOSURE_LEFT_EDGE; @@ -269,9 +281,9 @@ namespace realsense_camera rs_set_device_options(rs_device_, edge_options_, 4, edge_values_, 0); } - if(config.enable_depth == false) + if (config.enable_depth == false) { - if(enable_color_ == false) + if (enable_color_ == false) { ROS_INFO_STREAM ("RealSense Camera - Color stream is also disabled. Cannot disable depth stream"); config.enable_depth = true; @@ -287,15 +299,15 @@ namespace realsense_camera } } - void RealsenseNodelet::checkError () + void RealsenseNodelet::checkError() { if (rs_error_) { - ROS_ERROR_STREAM ("RealSense Camera - Error calling " << rs_get_failed_function (rs_error_) << " ( " - << rs_get_failed_args (rs_error_) << " ): \n" << rs_get_error_message (rs_error_) << " \n"); - rs_free_error (rs_error_); + ROS_ERROR_STREAM ("RealSense Camera - Error calling " << rs_get_failed_function(rs_error_) << " ( " + << rs_get_failed_args(rs_error_) << " ): \n" << rs_get_error_message(rs_error_) << " \n"); + rs_free_error(rs_error_); - ros::shutdown (); + ros::shutdown(); exit (EXIT_FAILURE); } @@ -304,15 +316,15 @@ namespace realsense_camera /* * Query the data for every frame and publish it to the different topics. */ - void RealsenseNodelet::devicePoll () + void RealsenseNodelet::devicePoll() { - while (ros::ok ()) + while (ros::ok()) { - publishStreams (); + publishStreams(); } } - bool RealsenseNodelet::connectToCamera () + bool RealsenseNodelet::connectToCamera() { if (enable_depth_ == false && enable_color_ == false) { @@ -321,26 +333,26 @@ namespace realsense_camera } rs_context_ = rs_create_context (RS_API_VERSION, &rs_error_); - checkError (); + checkError(); - int num_of_cameras = rs_get_device_count (rs_context_, NULL); + int num_of_cameras = rs_get_device_count(rs_context_, NULL); if (num_of_cameras < 1) { ROS_ERROR_STREAM ("RealSense Camera - No cameras are connected."); return false; } - rs_device_ = rs_get_device (rs_context_, 0, &rs_error_); - checkError (); + rs_device_ = rs_get_device(rs_context_, 0, &rs_error_); + checkError(); ROS_INFO_STREAM ("RealSense Camera - Number of cameras connected: " << num_of_cameras); ROS_INFO_STREAM ("RealSense Camera - Firmware version: " << - rs_get_device_firmware_version (rs_device_, &rs_error_)); - checkError (); - ROS_INFO_STREAM ("RealSense Camera - Name: " << rs_get_device_name (rs_device_, &rs_error_)); - checkError (); - ROS_INFO_STREAM ("RealSense Camera - Serial no: " << rs_get_device_serial (rs_device_, &rs_error_)); - checkError (); + rs_get_device_firmware_version(rs_device_, &rs_error_)); + checkError(); + ROS_INFO_STREAM ("RealSense Camera - Name: " << rs_get_device_name(rs_device_, &rs_error_)); + checkError(); + ROS_INFO_STREAM ("RealSense Camera - Serial no: " << rs_get_device_serial(rs_device_, &rs_error_)); + checkError(); // Enable streams. if (enable_color_ == true) @@ -359,12 +371,12 @@ namespace realsense_camera setStaticCameraOptions(); // Start device. - rs_start_device (rs_device_, &rs_error_); - checkError (); + rs_start_device(rs_device_, &rs_error_); + checkError(); is_device_started_ = true; - allocateResources (); + allocateResources(); return true; } @@ -394,31 +406,31 @@ namespace realsense_camera /* * Define buffer for images and prepare camera info for each enabled stream. */ - void RealsenseNodelet::allocateResources () + void RealsenseNodelet::allocateResources() { // Prepare camera for enabled streams (color/depth/infrared/infrared2). - fillStreamEncoding (); + fillStreamEncoding(); - image_[(uint32_t) RS_STREAM_COLOR] = cv::Mat (color_height_, color_width_, CV_8UC3, cv::Scalar (0, 0, 0)); - image_[(uint32_t) RS_STREAM_DEPTH] = cv::Mat (depth_height_, depth_width_, CV_16UC1, cv::Scalar (0)); - image_[(uint32_t) RS_STREAM_INFRARED] = cv::Mat (depth_height_, depth_width_, CV_8UC1, cv::Scalar (0)); - if (camera_.find (R200) != std::string::npos) + image_[(uint32_t) RS_STREAM_COLOR] = cv::Mat(color_height_, color_width_, CV_8UC3, cv::Scalar (0, 0, 0)); + image_[(uint32_t) RS_STREAM_DEPTH] = cv::Mat(depth_height_, depth_width_, CV_16UC1, cv::Scalar (0)); + image_[(uint32_t) RS_STREAM_INFRARED] = cv::Mat(depth_height_, depth_width_, CV_8UC1, cv::Scalar (0)); + if (camera_.find(R200) != std::string::npos) { - image_[(uint32_t) RS_STREAM_INFRARED2] = cv::Mat (depth_height_, depth_width_, CV_8UC1, cv::Scalar (0)); + image_[(uint32_t) RS_STREAM_INFRARED2] = cv::Mat(depth_height_, depth_width_, CV_8UC1, cv::Scalar (0)); } } /* * Prepare camera_info for each enabled stream. */ - void RealsenseNodelet::prepareStreamCalibData (rs_stream rs_strm) + void RealsenseNodelet::prepareStreamCalibData(rs_stream rs_strm) { uint32_t stream_index = (uint32_t) rs_strm; rs_intrinsics intrinsic; - rs_get_stream_intrinsics (rs_device_, rs_strm, &intrinsic, &rs_error_); - checkError (); + rs_get_stream_intrinsics(rs_device_, rs_strm, &intrinsic, &rs_error_); + checkError(); - camera_info_[stream_index] = new sensor_msgs::CameraInfo (); + camera_info_[stream_index] = new sensor_msgs::CameraInfo(); camera_info_ptr_[stream_index] = sensor_msgs::CameraInfoPtr (camera_info_[stream_index]); camera_info_[stream_index]->header.frame_id = frame_id_[stream_index]; @@ -450,7 +462,8 @@ namespace realsense_camera { // set depth to color translation values in Projection matrix (P) rs_extrinsics z_extrinsic; - rs_get_device_extrinsics (rs_device_, RS_STREAM_DEPTH, RS_STREAM_COLOR, &z_extrinsic, &rs_error_); checkError (); + rs_get_device_extrinsics(rs_device_, RS_STREAM_DEPTH, RS_STREAM_COLOR, &z_extrinsic, &rs_error_); + checkError(); camera_info_[stream_index]->P.at(3) = z_extrinsic.translation[0]/1000; // Tx camera_info_[stream_index]->P.at(7) = z_extrinsic.translation[1]/1000; // Ty camera_info_[stream_index]->P.at(11) = z_extrinsic.translation[2]/1000; // Tz @@ -470,7 +483,9 @@ namespace realsense_camera camera_info_[stream_index]->R.at(8) = (double) 1; for (int i = 0; i < 5; i++) - camera_info_[stream_index]->D.push_back (0); + { + camera_info_[stream_index]->D.push_back(0); + } } /* @@ -486,7 +501,7 @@ namespace realsense_camera { opt_name = rs_option_to_string(o.opt); o.value = rs_get_device_option(rs_device_, o.opt, 0); - opt_value = boost::lexical_cast < std::string > (o.value); + opt_value = boost::lexical_cast(o.value); get_options_result_str += opt_name + ":" + opt_value + ";"; } @@ -565,7 +580,7 @@ namespace realsense_camera opt_val = val; } ROS_INFO_STREAM ("RealSense Camera - Static Options: " << opt_name << " = " << opt_val); - rs_set_device_option (rs_device_, o.opt, opt_val, &rs_error_); + rs_set_device_option(rs_device_, o.opt, opt_val, &rs_error_); checkError(); } } @@ -575,24 +590,24 @@ namespace realsense_camera /* * Copy frame data from realsense to member cv images. */ - void RealsenseNodelet::prepareStreamData (rs_stream rs_strm) + void RealsenseNodelet::prepareStreamData(rs_stream rs_strm) { switch (rs_strm) { case RS_STREAM_COLOR: - image_[(uint32_t) RS_STREAM_COLOR].data = (unsigned char *) (rs_get_frame_data (rs_device_, RS_STREAM_COLOR, 0)); + image_[(uint32_t) RS_STREAM_COLOR].data = (unsigned char *) (rs_get_frame_data(rs_device_, RS_STREAM_COLOR, 0)); break; case RS_STREAM_DEPTH: - image_depth16_ = reinterpret_cast (rs_get_frame_data (rs_device_, RS_STREAM_DEPTH, 0)); + image_depth16_ = reinterpret_cast (rs_get_frame_data(rs_device_, RS_STREAM_DEPTH, 0)); image_[(uint32_t) RS_STREAM_DEPTH].data = (unsigned char *) image_depth16_; break; case RS_STREAM_INFRARED: image_[(uint32_t) RS_STREAM_INFRARED].data = - (unsigned char *) (rs_get_frame_data (rs_device_, RS_STREAM_INFRARED, 0)); + (unsigned char *) (rs_get_frame_data(rs_device_, RS_STREAM_INFRARED, 0)); break; case RS_STREAM_INFRARED2: image_[(uint32_t) RS_STREAM_INFRARED2].data = - (unsigned char *) (rs_get_frame_data (rs_device_, RS_STREAM_INFRARED2, 0)); + (unsigned char *) (rs_get_frame_data(rs_device_, RS_STREAM_INFRARED2, 0)); break; default: // no other streams supported @@ -603,7 +618,7 @@ namespace realsense_camera /* * Populate the encodings for each stream. */ - void RealsenseNodelet::fillStreamEncoding () + void RealsenseNodelet::fillStreamEncoding() { stream_encoding_[(uint32_t) RS_STREAM_COLOR] = "rgb8"; stream_step_[(uint32_t) RS_STREAM_COLOR] = color_width_ * sizeof (unsigned char) * 3; @@ -618,39 +633,45 @@ namespace realsense_camera /* * Publish streams. */ - void RealsenseNodelet::publishStreams () + void RealsenseNodelet::publishStreams() { - if(enable_depth_ == false && rs_is_stream_enabled (rs_device_, RS_STREAM_DEPTH, 0) == 1) + if (enable_depth_ == false && rs_is_stream_enabled(rs_device_, RS_STREAM_DEPTH, 0) == 1) { - if(rs_is_device_streaming(rs_device_, 0) == 1) + if (rs_is_device_streaming(rs_device_, 0) == 1) { - rs_stop_device (rs_device_, &rs_error_); checkError (); + rs_stop_device(rs_device_, &rs_error_); + checkError(); ROS_INFO_STREAM ("RealSense Camera - Device Stopped"); } //disable depth, infrared1 and infrared2 streams - rs_disable_stream(rs_device_, RS_STREAM_DEPTH, &rs_error_); checkError (); + rs_disable_stream(rs_device_, RS_STREAM_DEPTH, &rs_error_); + checkError(); ROS_INFO_STREAM ("RealSense Camera - Depth Stream Disabled"); - rs_disable_stream(rs_device_, RS_STREAM_INFRARED, &rs_error_); checkError (); + rs_disable_stream(rs_device_, RS_STREAM_INFRARED, &rs_error_); + checkError(); ROS_INFO_STREAM ("RealSense Camera - Infrared1 stream Disabled"); - rs_disable_stream(rs_device_, RS_STREAM_INFRARED2, &rs_error_); checkError (); + rs_disable_stream(rs_device_, RS_STREAM_INFRARED2, &rs_error_); + checkError(); ROS_INFO_STREAM ("RealSense Camera - Infrared2 stream Disabled"); - if(rs_is_device_streaming(rs_device_, 0) == 0) + if (rs_is_device_streaming(rs_device_, 0) == 0) { - rs_start_device (rs_device_, &rs_error_);checkError (); + rs_start_device(rs_device_, &rs_error_); + checkError(); ROS_INFO_STREAM ("RealSense Camera - Device Started"); } } - if(enable_depth_ == true && rs_is_stream_enabled (rs_device_, RS_STREAM_DEPTH, 0) == 0) + if (enable_depth_ == true && rs_is_stream_enabled(rs_device_, RS_STREAM_DEPTH, 0) == 0) { - if(rs_is_device_streaming(rs_device_, 0) == 1) + if (rs_is_device_streaming(rs_device_, 0) == 1) { - rs_stop_device (rs_device_, &rs_error_); checkError (); + rs_stop_device(rs_device_, &rs_error_); + checkError(); ROS_INFO_STREAM ("RealSense Camera - Device Stopped"); } @@ -658,30 +679,31 @@ namespace realsense_camera enableInfraredStream(); enableInfrared2Stream(); - if(rs_is_device_streaming(rs_device_, 0) == 0) + if (rs_is_device_streaming(rs_device_, 0) == 0) { - rs_start_device (rs_device_, &rs_error_); checkError (); + rs_start_device(rs_device_, &rs_error_); + checkError(); ROS_INFO_STREAM ("RealSense Camera - Device Started"); } } - if(rs_is_device_streaming(rs_device_, 0) == 1) + if (rs_is_device_streaming(rs_device_, 0) == 1) { - rs_wait_for_frames (rs_device_, &rs_error_); - checkError (); - time_stamp_ = ros::Time::now (); + rs_wait_for_frames(rs_device_, &rs_error_); + checkError(); + time_stamp_ = ros::Time::now(); for (int stream_index = 0; stream_index < STREAM_COUNT; ++stream_index) { // Publish image stream only if there is at least one subscriber. - if (camera_publisher_[stream_index].getNumSubscribers () > 0 && - rs_is_stream_enabled (rs_device_, (rs_stream) stream_index, 0) == 1) + if (camera_publisher_[stream_index].getNumSubscribers() > 0 && + rs_is_stream_enabled(rs_device_, (rs_stream) stream_index, 0) == 1) { prepareStreamData ((rs_stream) stream_index); - sensor_msgs::ImagePtr msg = cv_bridge::CvImage (std_msgs::Header (), + sensor_msgs::ImagePtr msg = cv_bridge::CvImage (std_msgs::Header(), stream_encoding_[stream_index], - image_[stream_index]).toImageMsg (); + image_[stream_index]).toImageMsg(); msg->header.frame_id = frame_id_[stream_index]; msg->header.stamp = time_stamp_; // Publish timestamp to synchronize frames. @@ -695,14 +717,14 @@ namespace realsense_camera } } - if (pointcloud_publisher_.getNumSubscribers () > 0 && rs_is_stream_enabled (rs_device_, RS_STREAM_DEPTH, 0) == 1 - && enable_pointcloud_ == true) + if (pointcloud_publisher_.getNumSubscribers() > 0 && + rs_is_stream_enabled(rs_device_, RS_STREAM_DEPTH, 0) == 1 && enable_pointcloud_ == true) { - if (camera_publisher_[(uint32_t) RS_STREAM_DEPTH].getNumSubscribers () <= 0) + if (camera_publisher_[(uint32_t) RS_STREAM_DEPTH].getNumSubscribers() <= 0) { prepareStreamData (RS_STREAM_DEPTH); } - if (camera_publisher_[(uint32_t) RS_STREAM_COLOR].getNumSubscribers () <= 0) + if (camera_publisher_[(uint32_t) RS_STREAM_COLOR].getNumSubscribers() <= 0) { prepareStreamData (RS_STREAM_COLOR); } @@ -717,19 +739,21 @@ namespace realsense_camera void RealsenseNodelet::publishPointCloud (cv::Mat & image_color) { // Publish pointcloud only if there is at least one subscriber. - if (pointcloud_publisher_.getNumSubscribers () > 0) + if (pointcloud_publisher_.getNumSubscribers() > 0) { rs_intrinsics color_intrinsic; rs_extrinsics z_extrinsic; rs_intrinsics z_intrinsic; - rs_get_stream_intrinsics (rs_device_, RS_STREAM_DEPTH, &z_intrinsic, &rs_error_); - checkError (); + rs_get_stream_intrinsics(rs_device_, RS_STREAM_DEPTH, &z_intrinsic, &rs_error_); + checkError(); if (enable_color_ == true) { - rs_get_stream_intrinsics (rs_device_, RS_STREAM_COLOR, &color_intrinsic, &rs_error_); checkError (); - rs_get_device_extrinsics (rs_device_, RS_STREAM_DEPTH, RS_STREAM_COLOR, &z_extrinsic, &rs_error_); checkError (); + rs_get_stream_intrinsics(rs_device_, RS_STREAM_COLOR, &color_intrinsic, &rs_error_); + checkError(); + rs_get_device_extrinsics(rs_device_, RS_STREAM_DEPTH, RS_STREAM_COLOR, &z_extrinsic, &rs_error_); + checkError(); } // Convert pointcloud from the camera to pointcloud object for ROS. @@ -739,28 +763,28 @@ namespace realsense_camera msg_pointcloud.header.stamp = time_stamp_; msg_pointcloud.is_dense = true; - sensor_msgs::PointCloud2Modifier modifier (msg_pointcloud); + sensor_msgs::PointCloud2Modifier modifier(msg_pointcloud); - modifier.setPointCloud2Fields (4, "x", 1, + modifier.setPointCloud2Fields(4, "x", 1, sensor_msgs::PointField::FLOAT32, "y", 1, sensor_msgs::PointField::FLOAT32, "z", 1, sensor_msgs::PointField::FLOAT32, "rgb", 1, sensor_msgs::PointField::FLOAT32); - modifier.setPointCloud2FieldsByString (2, "xyz", "rgb"); + modifier.setPointCloud2FieldsByString(2, "xyz", "rgb"); - sensor_msgs::PointCloud2Iterator < float >iter_x (msg_pointcloud, "x"); - sensor_msgs::PointCloud2Iterator < float >iter_y (msg_pointcloud, "y"); - sensor_msgs::PointCloud2Iterator < float >iter_z (msg_pointcloud, "z"); + sensor_msgs::PointCloud2Iteratoriter_x(msg_pointcloud, "x"); + sensor_msgs::PointCloud2Iteratoriter_y(msg_pointcloud, "y"); + sensor_msgs::PointCloud2Iteratoriter_z(msg_pointcloud, "z"); - sensor_msgs::PointCloud2Iterator < uint8_t > iter_r (msg_pointcloud, "r"); - sensor_msgs::PointCloud2Iterator < uint8_t > iter_g (msg_pointcloud, "g"); - sensor_msgs::PointCloud2Iterator < uint8_t > iter_b (msg_pointcloud, "b"); + sensor_msgs::PointCloud2Iteratoriter_r(msg_pointcloud, "r"); + sensor_msgs::PointCloud2Iteratoriter_g(msg_pointcloud, "g"); + sensor_msgs::PointCloud2Iteratoriter_b(msg_pointcloud, "b"); float depth_point[3], color_point[3], color_pixel[2], scaled_depth; unsigned char *color_data = image_color.data; - const float depth_scale = rs_get_device_depth_scale (rs_device_, &rs_error_); - checkError ();// Default value is 0.001 + const float depth_scale = rs_get_device_depth_scale(rs_device_, &rs_error_); + checkError();// Default value is 0.001 // Fill the PointCloud2 fields. for (int y = 0; y < z_intrinsic.height; y++) @@ -770,7 +794,7 @@ namespace realsense_camera scaled_depth = ((float) *image_depth16_) * depth_scale; float depth_pixel[2] = { (float) x, (float) y}; - rs_deproject_pixel_to_point (depth_point, &z_intrinsic, depth_pixel, scaled_depth); + rs_deproject_pixel_to_point(depth_point, &z_intrinsic, depth_pixel, scaled_depth); if (depth_point[2] <= 0 || depth_point[2] > MAX_Z) { @@ -790,8 +814,8 @@ namespace realsense_camera if (enable_color_ == true) { - rs_transform_point_to_point (color_point, &z_extrinsic, depth_point); - rs_project_point_to_pixel (color_pixel, &color_intrinsic, color_point); + rs_transform_point_to_point(color_point, &z_extrinsic, depth_point); + rs_project_point_to_pixel(color_pixel, &color_intrinsic, color_point); if (color_pixel[1] < 0 || color_pixel[1] > image_color.rows || color_pixel[0] < 0 || color_pixel[0] > image_color.cols) @@ -819,7 +843,7 @@ namespace realsense_camera } msg_pointcloud.header.frame_id = frame_id_[RS_STREAM_DEPTH]; - pointcloud_publisher_.publish (msg_pointcloud); + pointcloud_publisher_.publish(msg_pointcloud); } } /* @@ -835,7 +859,8 @@ namespace realsense_camera rs_extrinsics z_extrinsic; // extrinsics are offsets between the cameras - rs_get_device_extrinsics (rs_device_, RS_STREAM_DEPTH, RS_STREAM_COLOR, &z_extrinsic, &rs_error_); checkError (); + rs_get_device_extrinsics(rs_device_, RS_STREAM_DEPTH, RS_STREAM_COLOR, &z_extrinsic, &rs_error_); + checkError(); ros::Duration sleeper(0.1); // 100ms From 0d5785753f13210067855f7bb3678519af3aba82 Mon Sep 17 00:00:00 2001 From: Mark D Horn Date: Wed, 23 Mar 2016 23:26:15 -0700 Subject: [PATCH 081/124] Create default templates for Issues and PRs Provide users with templates providing guidelines on requested data related to submitted Issues and Pull Requests. --- .github/ISSUE_TEMPLATE.md | 32 ++++++++++++++++++++++++++++++++ .github/PULL_REQUEST_TEMPLATE.md | 8 ++++++++ 2 files changed, 40 insertions(+) create mode 100644 .github/ISSUE_TEMPLATE.md create mode 100644 .github/PULL_REQUEST_TEMPLATE.md diff --git a/.github/ISSUE_TEMPLATE.md b/.github/ISSUE_TEMPLATE.md new file mode 100644 index 0000000000..78e8f72d51 --- /dev/null +++ b/.github/ISSUE_TEMPLATE.md @@ -0,0 +1,32 @@ +### System Configuration +Please complete Your Configuration detail below. + +| Version | Known Good | Your Configuration | +| ---------------- | ------------:| ------------------:| +| Operating System | ubuntu 14.04 | ??? | +| Kernel Version | 4.4.0-13 | ?.?.?-? | +| R200 FW | 1.0.72.06 | ?.?.?.? | +| librealsense | 0.9.1 | ?.?.? | + +--- +#### How to collect Configuration Data +*This section can be delete before submission.* + +| Version | Method | +| ---------------- | ------------ | +| Operating System | `cat /etc/*elease*` | +| Kernel Version | `uname -r` | +| R200 FW | View the ROS log from running node **OR** `/librealsense/bin/cpp-enumerate-devices | grep -i firmware` | +| librealsense | `cat /librealsense/readme.md | grep release-image | awk -F- '{print $3}'` | +--- + + +### Expected Behavior + + +### Actual Behavior + + +### Steps to Reproduce + + diff --git a/.github/PULL_REQUEST_TEMPLATE.md b/.github/PULL_REQUEST_TEMPLATE.md new file mode 100644 index 0000000000..e0ebfd2a0d --- /dev/null +++ b/.github/PULL_REQUEST_TEMPLATE.md @@ -0,0 +1,8 @@ +Fixes Issue: # + +Changes proposed in this pull request: +- +- +- + + From b6f174dcc89dccfea9c4a349d5417f2cdadd2c22 Mon Sep 17 00:00:00 2001 From: rjingar Date: Wed, 23 Mar 2016 16:06:31 -0700 Subject: [PATCH 082/124] Modified parameters to lowercase for consistency --- camera/README.md | 72 +++++++++---------- camera/cfg/camera_params.cfg | 36 +++++----- camera/src/realsense_camera_nodelet.cpp | 60 ++++++++-------- ..._r200_dynamic_camera_options_params.launch | 56 +++++++-------- ...e_r200_static_camera_options_params.launch | 54 +++++++------- 5 files changed, 140 insertions(+), 138 deletions(-) diff --git a/camera/README.md b/camera/README.md index 12add2d210..4febe91674 100644 --- a/camera/README.md +++ b/camera/README.md @@ -98,19 +98,19 @@ Infrared2 camera Specify the camera name. Camera parameters: Following are the parameters that can be set only statically in the R200 camera: - R200_DEPTH_UNITS : [1, 2147483647] - R200_DEPTH_CLAMP_MIN : [0, 65535] - R200_DEPTH_CLAMP_MAX : [0, 65535] - R200_DEPTH_CONTROL_ESTIMATE_MEDIAN_DECREMENT : [0 - 255] - R200_DEPTH_CONTROL_ESTIMATE_MEDIAN_INCREMENT : [0 - 255] - R200_DEPTH_CONTROL_MEDIAN_THRESHOLD : [0 - 1023] - R200_DEPTH_CONTROL_SCORE_MINIMUM_THRESHOLD : [0 - 1023] - R200_DEPTH_CONTROL_SCORE_MAXIMUM_THRESHOLD : [0 - 1023] - R200_DEPTH_CONTROL_TEXTURE_COUNT_THRESHOLD : [0 - 31] - R200_DEPTH_CONTROL_TEXTURE_DIFFERENCE_THRESHOLD : [0 - 1023] - R200_DEPTH_CONTROL_SECOND_PEAK_THRESHOLD : [0 - 1023] - R200_DEPTH_CONTROL_NEIGHBOR_THRESHOLD : [0 - 1023] - R200_DEPTH_CONTROL_LR_THRESHOLD : [0 - 2047] + r200_depth_units : [1, 2147483647] + r200_depth_clamp_min : [0, 65535] + r200_depth_clamp_max : [0, 65535] + r200_depth_control_estimate_median_decrement : [0 - 255] + r200_depth_control_estimate_median_increment : [0 - 255] + r200_depth_control_median_threshold : [0 - 1023] + r200_depth_control_score_minimum_threshold : [0 - 1023] + r200_depth_control_score_maximum_threshold : [0 - 1023] + r200_depth_control_texture_count_threshold : [0 - 31] + r200_depth_control_texture_difference_threshold : [0 - 1023] + r200_depth_control_second_peak_threshold : [0 - 1023] + r200_depth_control_neighbor_threshold : [0 - 1023] + r200_depth_control_lr_threshold : [0 - 2047] ####Services get_settings (camera/get_settings) @@ -126,27 +126,27 @@ To get supported camera options with current value set. It returns string in opt Camera parameters: Following are the parameters that can be set dynamically as well as statically in the R200 camera. - COLOR_BACKLIGHT_COMPENSATION - COLOR_BRIGHTNESS - COLOR_CONTRAST - COLOR_GAIN - COLOR_GAMMA - COLOR_HUE - COLOR_SATURATION - COLOR_SHARPNESS - COLOR_ENABLE_AUTO_WHITE_BALANCE - COLOR_WHITE_BALANCE (Must be set only if COLOR_ENABLE_AUTO_WHITE_BALANCE is disabled) - R200_LR_GAIN - R200_EMITTER_ENABLED - R200_LR_EXPOSURE (Must be set only if R200_LR_AUTO_EXPOSURE_ENABLED is disabled) - Following are the parameters that can only be set dynamically in the R200 camera. - R200_LR_AUTO_EXPOSURE_ENABLED - R200_AUTO_EXPOSURE_TOP_EDGE (Must be set only if R200_LR_AUTO_EXPOSURE_ENABLED is enabled) - R200_AUTO_EXPOSURE_BOTTOM_EDGE (Must be set only if R200_LR_AUTO_EXPOSURE_ENABLED is enabled) - R200_AUTO_EXPOSURE_LEFT_EDGE (Must be set only if R200_LR_AUTO_EXPOSURE_ENABLED is enabled) - R200_AUTO_EXPOSURE_RIGHT_EDGE (Must be set only if R200_LR_AUTO_EXPOSURE_ENABLED is enabled) - -Note: For Autoexposure EDGE parameters, max value will go only upto the bounds of the infrared image. + color_backlight_compensation + color_brightness + color_contrast + color_gain + color_gamma + color_hue + color_saturation + color_sharpness + color_enable_auto_white_balance + color_white_balance (Must be set only if color_enable_auto_white_balance is disabled) + r200_lr_gain + r200_emitter_enabled + r200_lr_exposure (Must be set only if r200_lr_auto_exposure_enabled is disabled) + Following are the parameters that can only be set dynamically in the R200 camera. + r200_lr_auto_exposure_enabled + r200_auto_exposure_top_edge (Must be set only if r200_lr_auto_exposure_enabled is enabled) + r200_auto_exposure_bottom_edge (Must be set only if r200_lr_auto_exposure_enabled is enabled) + r200_auto_exposure_left_edge (Must be set only if r200_lr_auto_exposure_enabled is enabled) + r200_auto_exposure_right_edge (Must be set only if r200_lr_auto_exposure_enabled is enabled) + +Note: For Autoexposure edge parameters, max value will go only upto the bounds of the infrared image. E.g. For 320x240 infrared image, valid values are within 0-319 and 0-239) Use rqt_reconfigure GUI to view and edit the parameters that are accessible via dynamic_reconfigure. @@ -157,7 +157,7 @@ Command to launch GUI: Command to change dynamic parameters using commandline: $ rosrun dynamic_reconfigure dynparam set / - E.g. $ rosrun dynamic_reconfigure dynparam set /RealsenseNodelet COLOR_BACKLIGHT_COMPENSATION 2 + E.g. $ rosrun dynamic_reconfigure dynparam set /RealsenseNodelet color_backlight_compensation 2 ###Running the R200 nodelet @@ -249,7 +249,7 @@ Currently, the ROS camera nodelet only supports the following formats: * Depth stream: Y16 * Infrared stream: Y8 -Note: The camera does not provide hardware based depth registration/projector data. Hence the launch file "realsense_r200_rgbd.launch" will not generate data for the following topics: +Note: The camera does not provide hardware based depth registration/projector data. Hence the launch file "realsense_r200_rgbd.launch" will not generate data for the following topics: /camera/depth_registered/hw_registered/image_rect_raw /camera/depth_registered/points /camera/depth_registered/hw_registered/image_rect diff --git a/camera/cfg/camera_params.cfg b/camera/cfg/camera_params.cfg index 031bf75267..8619283ba5 100755 --- a/camera/cfg/camera_params.cfg +++ b/camera/cfg/camera_params.cfg @@ -8,23 +8,23 @@ gen = ParameterGenerator() # Name Type Level Description Default Min Max gen.add("enable_depth", bool_t, 0, "Enable Depth", True) -gen.add("COLOR_BACKLIGHT_COMPENSATION", int_t, 0, "Backlight Compensation", 1, 0, 4) -gen.add("COLOR_BRIGHTNESS", int_t, 0, "Brightness", 56, 0, 255) -gen.add("COLOR_CONTRAST", int_t, 0, "Contrast", 32, 16, 64) -gen.add("COLOR_GAIN", int_t, 0, "Gain", 32, 0, 256) -gen.add("COLOR_GAMMA", int_t, 0, "Gamma", 220, 100, 280) -gen.add("COLOR_HUE", int_t, 0, "Hue", 0, -2200, 2200) -gen.add("COLOR_SATURATION", int_t, 0, "Saturation", 128, 0, 255) -gen.add("COLOR_SHARPNESS", int_t, 0, "Sharpness", 0, 0, 7) -gen.add("COLOR_WHITE_BALANCE", int_t, 0, "White Balance", 6500, 2000, 8000) -gen.add("COLOR_ENABLE_AUTO_WHITE_BALANCE", int_t, 0, "Enable Auto White Balance", 1, 0, 1) -gen.add("R200_LR_AUTO_EXPOSURE_ENABLED", int_t, 0, "LR Auto Exposure Enabled", 0, 0, 1) -gen.add("R200_LR_GAIN", int_t, 0, "LR Gain", 400, 100, 6399) -gen.add("R200_LR_EXPOSURE", int_t, 0, "LR Exposure", 164, 1, 164) -gen.add("R200_EMITTER_ENABLED", int_t, 0, "Emitter Enabled", 1, 0, 1) -gen.add("R200_AUTO_EXPOSURE_TOP_EDGE", int_t, 0, "Auto Exposure Top Edge", 0, 0, 479) -gen.add("R200_AUTO_EXPOSURE_BOTTOM_EDGE", int_t, 0, "Auto Exposure Bottom Edge", 479, 0, 479) -gen.add("R200_AUTO_EXPOSURE_LEFT_EDGE", int_t, 0, "Auto Exposure Left Edge", 0, 0, 639) -gen.add("R200_AUTO_EXPOSURE_RIGHT_EDGE", int_t, 0, "Auto Exposure Right Edge", 639, 0, 639) +gen.add("color_backlight_compensation", int_t, 0, "Backlight Compensation", 1, 0, 4) +gen.add("color_brightness", int_t, 0, "Brightness", 56, 0, 255) +gen.add("color_contrast", int_t, 0, "Contrast", 32, 16, 64) +gen.add("color_gain", int_t, 0, "Gain", 32, 0, 256) +gen.add("color_gamma", int_t, 0, "Gamma", 220, 100, 280) +gen.add("color_hue", int_t, 0, "Hue", 0, -2200, 2200) +gen.add("color_saturation", int_t, 0, "Saturation", 128, 0, 255) +gen.add("color_sharpness", int_t, 0, "Sharpness", 0, 0, 7) +gen.add("color_white_balance", int_t, 0, "White Balance", 6500, 2000, 8000) +gen.add("color_enable_auto_white_balance", int_t, 0, "Enable Auto White Balance", 1, 0, 1) +gen.add("r200_lr_auto_exposure_enabled", int_t, 0, "LR Auto Exposure Enabled", 0, 0, 1) +gen.add("r200_lr_gain", int_t, 0, "LR Gain", 400, 100, 6399) +gen.add("r200_lr_exposure", int_t, 0, "LR Exposure", 164, 1, 164) +gen.add("r200_emitter_enabled", int_t, 0, "Emitter Enabled", 1, 0, 1) +gen.add("r200_auto_exposure_top_edge", int_t, 0, "Auto Exposure Top Edge", 0, 0, 479) +gen.add("r200_auto_exposure_bottom_edge", int_t, 0, "Auto Exposure Bottom Edge", 479, 0, 479) +gen.add("r200_auto_exposure_left_edge", int_t, 0, "Auto Exposure Left Edge", 0, 0, 639) +gen.add("r200_auto_exposure_right_edge", int_t, 0, "Auto Exposure Right Edge", 639, 0, 639) exit(gen.generate(PACKAGE, "realsense_camera", "camera_params")) diff --git a/camera/src/realsense_camera_nodelet.cpp b/camera/src/realsense_camera_nodelet.cpp index 4756ce5301..fa2473cb7b 100644 --- a/camera/src/realsense_camera_nodelet.cpp +++ b/camera/src/realsense_camera_nodelet.cpp @@ -229,54 +229,54 @@ namespace realsense_camera void RealsenseNodelet::configCallback(realsense_camera::camera_paramsConfig &config, uint32_t level) { - rs_set_device_option(rs_device_, RS_OPTION_COLOR_BACKLIGHT_COMPENSATION, config.COLOR_BACKLIGHT_COMPENSATION, 0); - rs_set_device_option(rs_device_, RS_OPTION_COLOR_BRIGHTNESS, config.COLOR_BRIGHTNESS, 0); - rs_set_device_option(rs_device_, RS_OPTION_COLOR_CONTRAST, config.COLOR_CONTRAST, 0); - rs_set_device_option(rs_device_, RS_OPTION_COLOR_GAIN, config.COLOR_GAIN, 0); - rs_set_device_option(rs_device_, RS_OPTION_COLOR_GAMMA, config.COLOR_GAMMA, 0); - rs_set_device_option(rs_device_, RS_OPTION_COLOR_HUE, config.COLOR_HUE, 0); - rs_set_device_option(rs_device_, RS_OPTION_COLOR_SATURATION, config.COLOR_SATURATION, 0); - rs_set_device_option(rs_device_, RS_OPTION_COLOR_SHARPNESS, config.COLOR_SHARPNESS, 0); - rs_set_device_option(rs_device_, RS_OPTION_COLOR_ENABLE_AUTO_WHITE_BALANCE, config.COLOR_ENABLE_AUTO_WHITE_BALANCE, 0); + rs_set_device_option(rs_device_, RS_OPTION_COLOR_BACKLIGHT_COMPENSATION, config.color_backlight_compensation, 0); + rs_set_device_option(rs_device_, RS_OPTION_COLOR_BRIGHTNESS, config.color_brightness, 0); + rs_set_device_option(rs_device_, RS_OPTION_COLOR_CONTRAST, config.color_contrast, 0); + rs_set_device_option(rs_device_, RS_OPTION_COLOR_GAIN, config.color_gain, 0); + rs_set_device_option(rs_device_, RS_OPTION_COLOR_GAMMA, config.color_gamma, 0); + rs_set_device_option(rs_device_, RS_OPTION_COLOR_HUE, config.color_hue, 0); + rs_set_device_option(rs_device_, RS_OPTION_COLOR_SATURATION, config.color_saturation, 0); + rs_set_device_option(rs_device_, RS_OPTION_COLOR_SHARPNESS, config.color_sharpness, 0); + rs_set_device_option(rs_device_, RS_OPTION_COLOR_ENABLE_AUTO_WHITE_BALANCE, config.color_enable_auto_white_balance, 0); - if (config.COLOR_ENABLE_AUTO_WHITE_BALANCE == 0) + if (config.color_enable_auto_white_balance == 0) { - rs_set_device_option(rs_device_, RS_OPTION_COLOR_WHITE_BALANCE, config.COLOR_WHITE_BALANCE, 0); + rs_set_device_option(rs_device_, RS_OPTION_COLOR_WHITE_BALANCE, config.color_white_balance, 0); } //R200 camera specific options - rs_set_device_option(rs_device_, RS_OPTION_R200_LR_AUTO_EXPOSURE_ENABLED, config.R200_LR_AUTO_EXPOSURE_ENABLED, 0); + rs_set_device_option(rs_device_, RS_OPTION_R200_LR_AUTO_EXPOSURE_ENABLED, config.r200_lr_auto_exposure_enabled, 0); - if (config.R200_LR_AUTO_EXPOSURE_ENABLED == 0) + if (config.r200_lr_auto_exposure_enabled == 0) { - rs_set_device_option(rs_device_, RS_OPTION_R200_LR_EXPOSURE, config.R200_LR_EXPOSURE, 0); + rs_set_device_option(rs_device_, RS_OPTION_R200_LR_EXPOSURE, config.r200_lr_exposure, 0); } - rs_set_device_option(rs_device_, RS_OPTION_R200_LR_GAIN, config.R200_LR_GAIN, 0); - rs_set_device_option(rs_device_, RS_OPTION_R200_EMITTER_ENABLED, config.R200_EMITTER_ENABLED, 0); + rs_set_device_option(rs_device_, RS_OPTION_R200_LR_GAIN, config.r200_lr_gain, 0); + rs_set_device_option(rs_device_, RS_OPTION_R200_EMITTER_ENABLED, config.r200_emitter_enabled, 0); - if (config.R200_LR_AUTO_EXPOSURE_ENABLED == 1) + if (config.r200_lr_auto_exposure_enabled == 1) { - if (config.R200_AUTO_EXPOSURE_TOP_EDGE >= depth_height_) + if (config.r200_auto_exposure_top_edge >= depth_height_) { - config.R200_AUTO_EXPOSURE_TOP_EDGE = depth_height_ - 1; + config.r200_auto_exposure_top_edge = depth_height_ - 1; } - if (config.R200_AUTO_EXPOSURE_BOTTOM_EDGE >= depth_height_) + if (config.r200_auto_exposure_bottom_edge >= depth_height_) { - config.R200_AUTO_EXPOSURE_BOTTOM_EDGE = depth_height_ - 1; + config.r200_auto_exposure_bottom_edge = depth_height_ - 1; } - if (config.R200_AUTO_EXPOSURE_LEFT_EDGE >= depth_width_) + if (config.r200_auto_exposure_left_edge >= depth_width_) { - config.R200_AUTO_EXPOSURE_LEFT_EDGE = depth_width_ - 1; + config.r200_auto_exposure_left_edge = depth_width_ - 1; } - if (config.R200_AUTO_EXPOSURE_RIGHT_EDGE >= depth_width_) + if (config.r200_auto_exposure_right_edge >= depth_width_) { - config.R200_AUTO_EXPOSURE_RIGHT_EDGE = depth_width_ - 1; + config.r200_auto_exposure_right_edge = depth_width_ - 1; } - edge_values_[0] = config.R200_AUTO_EXPOSURE_LEFT_EDGE; - edge_values_[1] = config.R200_AUTO_EXPOSURE_TOP_EDGE; - edge_values_[2] = config.R200_AUTO_EXPOSURE_RIGHT_EDGE; - edge_values_[3] = config.R200_AUTO_EXPOSURE_BOTTOM_EDGE; + edge_values_[0] = config.r200_auto_exposure_left_edge; + edge_values_[1] = config.r200_auto_exposure_top_edge; + edge_values_[2] = config.r200_auto_exposure_right_edge; + edge_values_[3] = config.r200_auto_exposure_bottom_edge; rs_set_device_options(rs_device_, edge_options_, 4, edge_values_, 0); } @@ -500,6 +500,7 @@ namespace realsense_camera for (option_str o: options) { opt_name = rs_option_to_string(o.opt); + std::transform(opt_name.begin(), opt_name.end(), opt_name.begin(), ::tolower); o.value = rs_get_device_option(rs_device_, o.opt, 0); opt_value = boost::lexical_cast(o.value); get_options_result_str += opt_name + ":" + opt_value + ";"; @@ -549,6 +550,7 @@ namespace realsense_camera std::vector::iterator it; for (camera_paramsConfig::AbstractParamDescriptionConstPtr param_desc_ptr: param_desc) { + std::transform(opt_name.begin(), opt_name.end(), opt_name.begin(), ::tolower); if (opt_name.compare((* param_desc_ptr).name) == 0) { found = true; diff --git a/camera/test/realsense_r200_dynamic_camera_options_params.launch b/camera/test/realsense_r200_dynamic_camera_options_params.launch index b57837cd3a..8529efe0c4 100644 --- a/camera/test/realsense_r200_dynamic_camera_options_params.launch +++ b/camera/test/realsense_r200_dynamic_camera_options_params.launch @@ -2,8 +2,8 @@ Launch file for testing if the dynamic camera options get set correctly using params. Steps: - roslaunch realsense_camera realsense_r200_static_camera_options_params.launch - rosrun realsense_camera realsense_camera_test COLOR_BACKLIGHT_COMPENSATION 3 COLOR_BRIGHTNESS 10 COLOR_CONTRAST 16 COLOR_GAIN 18 COLOR_GAMMA 100 COLOR_HUE 20 COLOR_SATURATION 21 COLOR_SHARPNESS 7 COLOR_ENABLE_AUTO_WHITE_BALANCE 0 COLOR_WHITE_BALANCE 3000 R200_LR_GAIN 200 R200_EMITTER_ENABLED 1 R200_LR_EXPOSURE 27 + roslaunch realsense_camera realsense_r200_dynamic_camera_options_params.launch + rosrun realsense_camera realsense_camera_test color_backlight_compensation 3 color_brightness 10 color_contrast 16 color_gain 18 color_gamma 100 color_hue 20 color_saturation 21 color_sharpness 7 color_enable_auto_white_balance 0 color_white_balance 3000 r200_lr_gain 200 r200_emitter_enabled 1 r200_lr_exposure 27 Verify that the "testCameraOptions" test pass. --> @@ -22,19 +22,19 @@ - - - - - - - - - - - - - + + + + + + + + + + + + + @@ -54,19 +54,19 @@ - - - - - - - - - - - - - + + + + + + + + + + + + + diff --git a/camera/test/realsense_r200_static_camera_options_params.launch b/camera/test/realsense_r200_static_camera_options_params.launch index 9ae48c0b6d..0e18fedac3 100644 --- a/camera/test/realsense_r200_static_camera_options_params.launch +++ b/camera/test/realsense_r200_static_camera_options_params.launch @@ -3,7 +3,7 @@ Steps: roslaunch realsense_camera realsense_r200_static_camera_options_params.launch - rosrun realsense_camera realsense_camera_test R200_DEPTH_UNITS 2 R200_DEPTH_CLAMP_MIN 3 R200_DEPTH_CLAMP_MAX 4 R200_DEPTH_CONTROL_ESTIMATE_MEDIAN_DECREMENT 5 R200_DEPTH_CONTROL_ESTIMATE_MEDIAN_INCREMENT 6 R200_DEPTH_CONTROL_MEDIAN_THRESHOLD 7 R200_DEPTH_CONTROL_SCORE_MINIMUM_THRESHOLD 8 R200_DEPTH_CONTROL_SCORE_MAXIMUM_THRESHOLD 9 R200_DEPTH_CONTROL_TEXTURE_COUNT_THRESHOLD 10 R200_DEPTH_CONTROL_TEXTURE_DIFFERENCE_THRESHOLD 11 R200_DEPTH_CONTROL_SECOND_PEAK_THRESHOLD 12 R200_DEPTH_CONTROL_NEIGHBOR_THRESHOLD 13 R200_DEPTH_CONTROL_LR_THRESHOLD 14 + rosrun realsense_camera realsense_camera_test r200_depth_units 2 r200_depth_clamp_min 3 r200_depth_clamp_max 4 r200_depth_control_estimate_median_decrement 5 r200_depth_control_estimate_median_increment 6 r200_depth_control_median_threshold 7 r200_depth_control_score_minimum_threshold 8 r200_depth_control_score_maximum_threshold 9 r200_depth_control_texture_count_threshold 10 r200_depth_control_texture_difference_threshold 11 r200_depth_control_second_peak_threshold 12 r200_depth_control_neighbor_threshold 13 r200_depth_control_lr_threshold 14 Verify that the "testCameraOptions" test pass. --> @@ -11,19 +11,19 @@ - - - - - - - - - - - - - + + + + + + + + + + + + + @@ -31,19 +31,19 @@ args="load realsense_camera/RealsenseNodelet standalone_nodelet"> - - - - - - - - - - - - - + + + + + + + + + + + + + From c4664a01b6eb6e5f7b3aec8bde393015b11c8d88 Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Tue, 22 Mar 2016 17:41:11 -0700 Subject: [PATCH 083/124] Added functionality to access camera using Serial No: Removed default Serial No: Added code to handle various use cases for input serial number Exit with error if no serial number is specified and multiple cameras are detected. Exit with error if no camera is detected that matches the input serial number. Updated launch files with a placeholder for serial number Updated rgbd_launch test code to remove hardcoded topic names. Updated README with changes related to serial number Apart from the serial number changes, updated the Limitations section to highlight that the nodelet only works for R200 Corrected rgbd_launch and README files Added code to print all the detected cameras. Removed leading spaces in few function calls --- camera/README.md | 34 ++++--- .../realsense_r200_nodelet.launch.xml | 3 +- .../launch/realsense_r200_navigation.launch | 3 +- ...ense_r200_nodelet_standalone_manual.launch | 2 + ...ense_r200_nodelet_standalone_preset.launch | 3 +- camera/launch/realsense_r200_rgbd.launch | 9 +- camera/src/realsense_camera_nodelet.cpp | 78 +++++++++++++--- camera/src/realsense_camera_nodelet.h | 6 +- .../test/realsense_camera_test_rgbd_node.cpp | 91 ++++++++++++------- camera/test/realsense_camera_test_rgbd_node.h | 60 ++++++++---- 10 files changed, 209 insertions(+), 80 deletions(-) diff --git a/camera/README.md b/camera/README.md index 4febe91674..d512a13bf5 100644 --- a/camera/README.md +++ b/camera/README.md @@ -73,6 +73,9 @@ Infrared2 camera #### Static Parameters Stream parameters: + serial_no (string, default: blank) + Specify the serial_no to uniquely connect to a camera, especially if multiple cameras are detected by the nodelet. + This feature has been tested to work only on kernel version 4.4.0-040400-generic. mode (string, default: preset) Specify the mode to start camera streams. Mode comprises of height, width and fps. Preset mode enables default values whereas Manual mode enables the specified parameter values. @@ -244,17 +247,22 @@ Refer to the function definitions in [realsense_camera_nodelet.h](src/realsense_ ###Limitations: -Currently, the ROS camera nodelet only supports the following formats: -* Color stream: RGB8 -* Depth stream: Y16 -* Infrared stream: Y8 - -Note: The camera does not provide hardware based depth registration/projector data. Hence the launch file "realsense_r200_rgbd.launch" will not generate data for the following topics: -/camera/depth_registered/hw_registered/image_rect_raw -/camera/depth_registered/points -/camera/depth_registered/hw_registered/image_rect -/camera/depth_registered/image -/camera/depth/disparity -/camera/depth_registered/disparity - +* Currently, the camera nodelet has been tested to work only for R200 cameras. + +* Currently, the camera nodelet only supports the following formats: + * Color stream: RGB8 + * Depth stream: Y16 + * Infrared stream: Y8 + +* The camera does not provide hardware based depth registration/projector data. +Hence the launch file "realsense_r200_rgbd.launch" will not generate data for the following topics: + * /camera/depth_registered/hw_registered/image_rect_raw + * /camera/depth_registered/points + * /camera/depth_registered/hw_registered/image_rect + * /camera/depth_registered/image + * /camera/depth/disparity + * /camera/depth_registered/disparity + +* If there are multiple R200 cameras connected to a system, the nodelet can be launched for a particular camera +by specifing the serial_no parameter in the launch file. But it has not been tested to launch nodelets simultaneouly for multiple cameras. diff --git a/camera/launch/includes/realsense_r200_nodelet.launch.xml b/camera/launch/includes/realsense_r200_nodelet.launch.xml index 361fe6ed63..97f64f3912 100644 --- a/camera/launch/includes/realsense_r200_nodelet.launch.xml +++ b/camera/launch/includes/realsense_r200_nodelet.launch.xml @@ -1,7 +1,6 @@ - @@ -9,6 +8,7 @@ + @@ -25,6 +25,7 @@ + diff --git a/camera/launch/realsense_r200_navigation.launch b/camera/launch/realsense_r200_navigation.launch index 1a4105604d..9ca8d38cb3 100644 --- a/camera/launch/realsense_r200_navigation.launch +++ b/camera/launch/realsense_r200_navigation.launch @@ -1,5 +1,5 @@ - + @@ -10,6 +10,7 @@ + diff --git a/camera/launch/realsense_r200_nodelet_standalone_manual.launch b/camera/launch/realsense_r200_nodelet_standalone_manual.launch index c4159e27dd..e66365bba4 100644 --- a/camera/launch/realsense_r200_nodelet_standalone_manual.launch +++ b/camera/launch/realsense_r200_nodelet_standalone_manual.launch @@ -1,5 +1,6 @@ + @@ -16,6 +17,7 @@ + diff --git a/camera/launch/realsense_r200_nodelet_standalone_preset.launch b/camera/launch/realsense_r200_nodelet_standalone_preset.launch index dd3d1a09c0..186d2e12bf 100644 --- a/camera/launch/realsense_r200_nodelet_standalone_preset.launch +++ b/camera/launch/realsense_r200_nodelet_standalone_preset.launch @@ -1,5 +1,5 @@ - + @@ -10,6 +10,7 @@ + diff --git a/camera/launch/realsense_r200_rgbd.launch b/camera/launch/realsense_r200_rgbd.launch index 4a9e760ac7..e1a51a40a6 100644 --- a/camera/launch/realsense_r200_rgbd.launch +++ b/camera/launch/realsense_r200_rgbd.launch @@ -1,9 +1,13 @@ - + + + + + @@ -51,6 +55,7 @@ + diff --git a/camera/src/realsense_camera_nodelet.cpp b/camera/src/realsense_camera_nodelet.cpp index fa2473cb7b..b7abe1395a 100644 --- a/camera/src/realsense_camera_nodelet.cpp +++ b/camera/src/realsense_camera_nodelet.cpp @@ -328,30 +328,59 @@ namespace realsense_camera { if (enable_depth_ == false && enable_color_ == false) { - ROS_INFO_STREAM ("RealSense Camera - None of the streams are enabled. Exiting."); + ROS_ERROR_STREAM("RealSense Camera - None of the streams are enabled. Exiting."); return false; } - rs_context_ = rs_create_context (RS_API_VERSION, &rs_error_); + rs_context_ = rs_create_context(RS_API_VERSION, &rs_error_); checkError(); - int num_of_cameras = rs_get_device_count(rs_context_, NULL); - if (num_of_cameras < 1) + num_of_cameras_ = rs_get_device_count(rs_context_, &rs_error_); + checkError(); + + // Exit with error if no cameras are connected. + if (num_of_cameras_ < 1) { - ROS_ERROR_STREAM ("RealSense Camera - No cameras are connected."); + ROS_ERROR_STREAM("RealSense Camera - No cameras detected. Exiting!"); return false; } - rs_device_ = rs_get_device(rs_context_, 0, &rs_error_); - checkError(); + rs_device_ = getCameraBySerialNumber(); // Get rs_device_ using input serial number. + + // Exit with error if no serial number is specified and multiple cameras are detected. + if ((serial_no_.empty() == true) && (num_of_cameras_ > 1)) + { + ROS_INFO_STREAM("RealSense Camera - Following cameras detected:"); + for (rs_device *rs_detected_device: rs_detected_devices_) + { + ROS_INFO_STREAM("Serial No: " << rs_get_device_serial(rs_detected_device, &rs_error_) << + " Firmware Version: " << rs_get_device_firmware_version(rs_detected_device, &rs_error_) << + " Name: " << rs_get_device_name(rs_detected_device, &rs_error_)); + } + ROS_ERROR_STREAM("RealSense Camera - Multiple cameras detected but no input serial_no specified. Exiting!"); + return false; + } + + // Exit with error if no camera is detected that matches the input serial number. + if ((serial_no_.empty() != true) && (rs_device_ == NULL)) + { + ROS_ERROR_STREAM("RealSense Camera - No camera detected with input serial_no = " << serial_no_ << ". Exiting!"); + return false; + } + + // At this point, rs_device_ will be null if no input serial number was specified and only one camera is connected. + // This is a valid use case and the code will proceed. + if (rs_device_ == NULL) + { + rs_device_ = rs_get_device(rs_context_, 0, &rs_error_); + checkError(); + } - ROS_INFO_STREAM ("RealSense Camera - Number of cameras connected: " << num_of_cameras); - ROS_INFO_STREAM ("RealSense Camera - Firmware version: " << - rs_get_device_firmware_version(rs_device_, &rs_error_)); + ROS_INFO_STREAM("RealSense Camera - Serial no: " << rs_get_device_serial(rs_device_, &rs_error_)); checkError(); - ROS_INFO_STREAM ("RealSense Camera - Name: " << rs_get_device_name(rs_device_, &rs_error_)); + ROS_INFO_STREAM("RealSense Camera - Firmware version: " << rs_get_device_firmware_version(rs_device_, &rs_error_)); checkError(); - ROS_INFO_STREAM ("RealSense Camera - Serial no: " << rs_get_device_serial(rs_device_, &rs_error_)); + ROS_INFO_STREAM("RealSense Camera - Name: " << rs_get_device_name(rs_device_, &rs_error_)); checkError(); // Enable streams. @@ -381,6 +410,30 @@ namespace realsense_camera return true; } + /* + * Returns the device details of the camera that matches the input serial_no. + * Returns NULL if no camera is found that matches the input serial_no. + * Also populates the list of detected cameras. + */ + rs_device * RealsenseNodelet::getCameraBySerialNumber() + { + rs_device *rs_device_detect; + rs_device *rs_device_connect = NULL; + for (int i = 0; i < num_of_cameras_; ++i) + { + rs_device_detect = rs_get_device(rs_context_, i, &rs_error_); + checkError(); + std::string device_serial_no = rs_get_device_serial(rs_device_detect, &rs_error_); + checkError(); + if (device_serial_no.compare(serial_no_) == 0) + { + rs_device_connect = rs_device_detect; + } + rs_detected_devices_.push_back(rs_device_detect); + } + return rs_device_connect; + } + /* * Gets the options supported by the camera along with their min, max and step values. */ @@ -515,6 +568,7 @@ namespace realsense_camera */ void RealsenseNodelet::setStreamOptions() { + pnh_.getParam("serial_no", serial_no_); pnh_.param("camera", camera_, (std::string) R200); pnh_.param("mode", mode_, DEFAULT_MODE); pnh_.param("enable_depth", enable_depth_, ENABLE_DEPTH); diff --git a/camera/src/realsense_camera_nodelet.h b/camera/src/realsense_camera_nodelet.h index 665d37a82e..0354588d83 100644 --- a/camera/src/realsense_camera_nodelet.h +++ b/camera/src/realsense_camera_nodelet.h @@ -76,7 +76,6 @@ class RealsenseNodelet: public nodelet::Nodelet // Default Constants. const int MAX_Z = 8; // in meters - const int DEFAULT_CAMERA = 0; // default camera index const std::string DEFAULT_MODE = "preset"; const int DEPTH_HEIGHT = 360; const int DEPTH_WIDTH = 480; @@ -88,7 +87,6 @@ class RealsenseNodelet: public nodelet::Nodelet const bool ENABLE_COLOR = true; const bool ENABLE_PC = true; const bool ENABLE_TF = true; - const uint32_t SERIAL_NUMBER = 0xFFFFFFFF; const rs_format DEPTH_FORMAT = RS_FORMAT_Z16; const rs_format COLOR_FORMAT = RS_FORMAT_RGB8; const rs_format IR1_FORMAT = RS_FORMAT_Y8; @@ -117,7 +115,10 @@ class RealsenseNodelet: public nodelet::Nodelet rs_error *rs_error_ = 0; rs_context *rs_context_; rs_device *rs_device_; + std::vector rs_detected_devices_; + int num_of_cameras_; + std::string serial_no_; int color_height_; int color_width_; int depth_height_; @@ -181,6 +182,7 @@ class RealsenseNodelet: public nodelet::Nodelet void getCameraOptions(); void allocateResources(); bool connectToCamera(); + rs_device * getCameraBySerialNumber(); void fillStreamEncoding(); void setStreamOptions(); void setStaticCameraOptions(); diff --git a/camera/test/realsense_camera_test_rgbd_node.cpp b/camera/test/realsense_camera_test_rgbd_node.cpp index d3cf52ecca..c90361eb40 100644 --- a/camera/test/realsense_camera_test_rgbd_node.cpp +++ b/camera/test/realsense_camera_test_rgbd_node.cpp @@ -8,12 +8,12 @@ 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. - 2. Redistributions in binary form must reproduce the above copyright notice, - this list of conditions and the following disclaimer in the documentation + 2. Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. - 3. Neither the name of the copyright holder nor the names of its contributors - may be used to endorse or promote products derived from this software without + 3. Neither the name of the copyright holder nor the names of its contributors + may be used to endorse or promote products derived from this software without specific prior written permission. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" @@ -135,71 +135,98 @@ void topic12Callback(const sensor_msgs::ImageConstPtr msg) } } -TEST (RealsenseTests, RGB_IMAGE_MONO) +TEST (RealsenseTests, rgb_image_mono) { EXPECT_TRUE (topic_0_recv); } -TEST (RealsenseTests, RGB_IMAGE_COLOR) +TEST (RealsenseTests, rgb_image_color) { EXPECT_TRUE (topic_1_recv); } -TEST (RealsenseTests, RGB_IMAGE_RECT_MONO) +TEST (RealsenseTests, rgb_image_rect_mono) { EXPECT_TRUE (topic_2_recv); } -TEST (RealsenseTests, RGB_IMAGE_RECT_COLOR) +TEST (RealsenseTests, rgb_image_rect_color) { EXPECT_TRUE (topic_3_recv); } -TEST (RealsenseTests, DEPTH_IMAGE_RECT_RAW) +TEST (RealsenseTests, depth_image_rect_raw) { EXPECT_TRUE (topic_4_recv); } -TEST (RealsenseTests, DEPTH_IMAGE_RECT) +TEST (RealsenseTests, depth_image_rect) { EXPECT_TRUE (topic_5_recv); } -TEST (RealsenseTests, DEPTH_IMAGE) +TEST (RealsenseTests, depth_image) { EXPECT_TRUE (topic_6_recv); } -TEST (RealsenseTests, DEPTH_POINTS) +TEST (RealsenseTests, depth_points) { EXPECT_TRUE (topic_7_recv); } -TEST (RealsenseTests, IR_IMAGE_RECT_IR) +TEST (RealsenseTests, ir_image_rect_ir) { EXPECT_TRUE (topic_8_recv); } -TEST (RealsenseTests, DEPTH_REG_SW_REG_IMAGE_RECT_RAW) +TEST (RealsenseTests, depth_reg_sw_reg_image_rect_raw) { EXPECT_TRUE (topic_9_recv); } -TEST (RealsenseTests, DEPTH_REG_SW_REG_CAMERA_INFO) +TEST (RealsenseTests, depth_reg_sw_reg_camera_info) { EXPECT_TRUE (topic_10_recv); } -TEST (RealsenseTests, DEPTH_REG_POINTS) +TEST (RealsenseTests, depth_reg_points) { EXPECT_TRUE (topic_11_recv); } -TEST (RealsenseTests, DEPTH_REG_SW_REG_IMAGE_RECT) +TEST (RealsenseTests, depth_reg_sw_reg_image_rect) { EXPECT_TRUE (topic_12_recv); } +void getParams() +{ + ros::NodeHandle pnh; + pnh.param("camera", camera, CAMERA); + pnh.param("rgb", rgb, RGB); + pnh.param("depth", depth, DEPTH); + pnh.param("ir", ir, IR); + pnh.param("depth_registered", depth_registered, DEPTH_REGISTERED); +} + +void setTopics() +{ + rgb_image_mono = "/" + camera + "/" + rgb + "/" + RGB_IMAGE_MONO; + rgb_image_color = "/" + camera + "/" + rgb + "/" + RGB_IMAGE_COLOR; + rgb_image_rect_mono = "/" + camera + "/" + rgb + "/" + RGB_IMAGE_RECT_MONO; + rgb_image_rect_color = "/" + camera + "/" + rgb + "/" + RGB_IMAGE_RECT_COLOR; + depth_image_rect_raw = "/" + camera + "/" + depth + "/" + DEPTH_IMAGE_RECT_RAW; + depth_image_rect = "/" + camera + "/" + depth + "/" + DEPTH_IMAGE_RECT; + depth_image = "/" + camera + "/" + depth + "/" + DEPTH_IMAGE; + depth_points = "/" + camera + "/" + depth + "/" + DEPTH_POINTS; + ir_image_rect_ir = "/" + camera + "/" + ir + "/" + IR_IMAGE_RECT_IR; + depth_reg_sw_reg_image_rect_raw = "/" + camera + "/" + depth_registered + "/" + DEPTH_REG_SW_REG_IMAGE_RECT_RAW; + depth_reg_sw_reg_camera_info = "/" + camera + "/" + depth_registered + "/" + DEPTH_REG_SW_REG_CAMERA_INFO; + depth_reg_points = "/" + camera + "/" + depth_registered + "/" + DEPTH_REG_POINTS; + depth_reg_sw_reg_image_rect = "/" + depth_registered + "/" + depth + "/" + DEPTH_REG_SW_REG_IMAGE_RECT; +} + int main(int argc, char **argv) { testing::InitGoogleTest(&argc, argv); @@ -208,20 +235,22 @@ int main(int argc, char **argv) ROS_INFO_STREAM("RealSense Camera - Starting rgbd_launch Tests..."); ros::NodeHandle nh; - - subscriber[0] = nh.subscribe < sensor_msgs::Image > (RGB_IMAGE_MONO, 1, topic0Callback, 0); - subscriber[1] = nh.subscribe < sensor_msgs::Image > (RGB_IMAGE_COLOR, 1, topic1Callback, 0); - subscriber[2] = nh.subscribe < sensor_msgs::Image > (RGB_IMAGE_RECT_MONO, 1, topic2Callback, 0); - subscriber[3] = nh.subscribe < sensor_msgs::Image > (RGB_IMAGE_RECT_COLOR, 1, topic3Callback, 0); - subscriber[4] = nh.subscribe < sensor_msgs::Image > (DEPTH_IMAGE_RECT_RAW, 1, topic4Callback, 0); - subscriber[5] = nh.subscribe < sensor_msgs::Image > (DEPTH_IMAGE_RECT, 1, topic5Callback, 0); - subscriber[6] = nh.subscribe < sensor_msgs::Image > (DEPTH_IMAGE, 1, topic6Callback, 0); - subscriber[7] = nh.subscribe < sensor_msgs::PointCloud2 > (DEPTH_POINTS, 1, topic7Callback); - subscriber[8] = nh.subscribe < sensor_msgs::Image > (IR_IMAGE_RECT_IR, 1, topic8Callback, 0); - subscriber[9] = nh.subscribe < sensor_msgs::Image > (DEPTH_REG_SW_REG_IMAGE_RECT_RAW, 1, topic9Callback, 0); - subscriber[10] = nh.subscribe < sensor_msgs::CameraInfo > (DEPTH_REG_SW_REG_CAMERA_INFO, 1, topic10Callback); - subscriber[11] = nh.subscribe < sensor_msgs::PointCloud2 > (DEPTH_REG_POINTS, 1, topic11Callback, 0); - subscriber[12] = nh.subscribe < sensor_msgs::Image > (DEPTH_REG_SW_REG_IMAGE_RECT, 1, topic12Callback, 0); + getParams(); + setTopics(); + + subscriber[0] = nh.subscribe(rgb_image_mono, 1, topic0Callback, 0); + subscriber[1] = nh.subscribe(rgb_image_color, 1, topic1Callback, 0); + subscriber[2] = nh.subscribe(rgb_image_rect_mono, 1, topic2Callback, 0); + subscriber[3] = nh.subscribe(rgb_image_rect_color, 1, topic3Callback, 0); + subscriber[4] = nh.subscribe(depth_image_rect_raw, 1, topic4Callback, 0); + subscriber[5] = nh.subscribe(depth_image_rect, 1, topic5Callback, 0); + subscriber[6] = nh.subscribe(depth_image, 1, topic6Callback, 0); + subscriber[7] = nh.subscribe(depth_points, 1, topic7Callback); + subscriber[8] = nh.subscribe(ir_image_rect_ir, 1, topic8Callback, 0); + subscriber[9] = nh.subscribe(depth_reg_sw_reg_image_rect_raw, 1, topic9Callback, 0); + subscriber[10] = nh.subscribe(depth_reg_sw_reg_camera_info, 1, topic10Callback); + subscriber[11] = nh.subscribe(depth_reg_points, 1, topic11Callback, 0); + subscriber[12] = nh.subscribe(depth_reg_sw_reg_image_rect, 1, topic12Callback, 0); ros::Duration duration; duration.sec = 10; diff --git a/camera/test/realsense_camera_test_rgbd_node.h b/camera/test/realsense_camera_test_rgbd_node.h index 1f4713e491..b78ea68dcd 100644 --- a/camera/test/realsense_camera_test_rgbd_node.h +++ b/camera/test/realsense_camera_test_rgbd_node.h @@ -8,12 +8,12 @@ 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. - 2. Redistributions in binary form must reproduce the above copyright notice, - this list of conditions and the following disclaimer in the documentation + 2. Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. - 3. Neither the name of the copyright holder nor the names of its contributors - may be used to endorse or promote products derived from this software without + 3. Neither the name of the copyright holder nor the names of its contributors + may be used to endorse or promote products derived from this software without specific prior written permission. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" @@ -37,19 +37,45 @@ const static int TOPIC_COUNT = 13; -const char *RGB_IMAGE_MONO = "/camera/rgb/image_mono"; -const char *RGB_IMAGE_COLOR = "/camera/rgb/image_color"; -const char *RGB_IMAGE_RECT_MONO = "/camera/rgb/image_rect_mono"; -const char *RGB_IMAGE_RECT_COLOR = "/camera/rgb/image_rect_color"; -const char *DEPTH_IMAGE_RECT_RAW = "/camera/depth/image_rect_raw"; -const char *DEPTH_IMAGE_RECT = "/camera/depth/image_rect"; -const char *DEPTH_IMAGE = "/camera/depth/image"; -const char *DEPTH_POINTS = "/camera/depth/points"; -const char *IR_IMAGE_RECT_IR = "/camera/ir/image_rect_ir"; -const char *DEPTH_REG_SW_REG_IMAGE_RECT_RAW = "/camera/depth_registered/sw_registered/image_rect_raw"; -const char *DEPTH_REG_SW_REG_CAMERA_INFO = "/camera/depth_registered/sw_registered/camera_info"; -const char *DEPTH_REG_POINTS = "/camera/depth_registered/points"; -const char *DEPTH_REG_SW_REG_IMAGE_RECT = "/camera/depth_registered/sw_registered/image_rect"; +std::string RGB_IMAGE_MONO = "image_mono"; +std::string RGB_IMAGE_COLOR = "image_color"; +std::string RGB_IMAGE_RECT_MONO = "image_rect_mono"; +std::string RGB_IMAGE_RECT_COLOR = "image_rect_color"; +std::string DEPTH_IMAGE_RECT_RAW = "image_rect_raw"; +std::string DEPTH_IMAGE_RECT = "image_rect"; +std::string DEPTH_IMAGE = "image"; +std::string DEPTH_POINTS = "points"; +std::string IR_IMAGE_RECT_IR = "image_rect_ir"; +std::string DEPTH_REG_SW_REG_IMAGE_RECT_RAW = "sw_registered/image_rect_raw"; +std::string DEPTH_REG_SW_REG_CAMERA_INFO = "sw_registered/camera_info"; +std::string DEPTH_REG_POINTS = "points"; +std::string DEPTH_REG_SW_REG_IMAGE_RECT = "sw_registered/image_rect"; + +std::string CAMERA = "camera"; +std::string RGB = "rgb"; +std::string DEPTH = "depth"; +std::string IR = "ir"; +std::string DEPTH_REGISTERED = "depth_registered"; + +std::string camera; +std::string rgb; +std::string depth; +std::string ir; +std::string depth_registered; + +std::string rgb_image_mono; +std::string rgb_image_color; +std::string rgb_image_rect_mono; +std::string rgb_image_rect_color; +std::string depth_image_rect_raw; +std::string depth_image_rect; +std::string depth_image; +std::string depth_points; +std::string ir_image_rect_ir; +std::string depth_reg_sw_reg_image_rect_raw; +std::string depth_reg_sw_reg_camera_info; +std::string depth_reg_points; +std::string depth_reg_sw_reg_image_rect; bool topic_0_recv = false; bool topic_1_recv = false; From a76f6be8cd23039079c1c4c6581159ef26c180e5 Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Thu, 24 Mar 2016 19:35:23 -0700 Subject: [PATCH 084/124] Updated code to always show detected cameras --- camera/src/realsense_camera_nodelet.cpp | 24 ++++++++++++------------ 1 file changed, 12 insertions(+), 12 deletions(-) diff --git a/camera/src/realsense_camera_nodelet.cpp b/camera/src/realsense_camera_nodelet.cpp index b7abe1395a..56f7677cfe 100644 --- a/camera/src/realsense_camera_nodelet.cpp +++ b/camera/src/realsense_camera_nodelet.cpp @@ -346,17 +346,20 @@ namespace realsense_camera } rs_device_ = getCameraBySerialNumber(); // Get rs_device_ using input serial number. + std::string detected_camera_msg = "RealSense Camera - Detected following cameras:"; + for (rs_device *rs_detected_device: rs_detected_devices_) + { + detected_camera_msg = detected_camera_msg + + "\n\t\t\t\t- Serial No: " + rs_get_device_serial(rs_detected_device, &rs_error_) + + "; Firmware: " + rs_get_device_firmware_version(rs_detected_device, &rs_error_) + + "; Name: " + rs_get_device_name(rs_detected_device, &rs_error_); + checkError(); + } + ROS_INFO_STREAM(detected_camera_msg); // Exit with error if no serial number is specified and multiple cameras are detected. if ((serial_no_.empty() == true) && (num_of_cameras_ > 1)) { - ROS_INFO_STREAM("RealSense Camera - Following cameras detected:"); - for (rs_device *rs_detected_device: rs_detected_devices_) - { - ROS_INFO_STREAM("Serial No: " << rs_get_device_serial(rs_detected_device, &rs_error_) << - " Firmware Version: " << rs_get_device_firmware_version(rs_detected_device, &rs_error_) << - " Name: " << rs_get_device_name(rs_detected_device, &rs_error_)); - } ROS_ERROR_STREAM("RealSense Camera - Multiple cameras detected but no input serial_no specified. Exiting!"); return false; } @@ -376,11 +379,8 @@ namespace realsense_camera checkError(); } - ROS_INFO_STREAM("RealSense Camera - Serial no: " << rs_get_device_serial(rs_device_, &rs_error_)); - checkError(); - ROS_INFO_STREAM("RealSense Camera - Firmware version: " << rs_get_device_firmware_version(rs_device_, &rs_error_)); - checkError(); - ROS_INFO_STREAM("RealSense Camera - Name: " << rs_get_device_name(rs_device_, &rs_error_)); + ROS_INFO_STREAM("RealSense Camera - Connecting to camera with Serial No: " << + rs_get_device_serial(rs_device_, &rs_error_)); checkError(); // Enable streams. From 6239f9e7c6a4fb8acb458739b5a682201bf1e014 Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Fri, 25 Mar 2016 14:19:18 -0700 Subject: [PATCH 085/124] Updated rgbd test file to correct a topic name --- camera/test/realsense_camera_test_rgbd_node.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/camera/test/realsense_camera_test_rgbd_node.cpp b/camera/test/realsense_camera_test_rgbd_node.cpp index c90361eb40..0ff6d23295 100644 --- a/camera/test/realsense_camera_test_rgbd_node.cpp +++ b/camera/test/realsense_camera_test_rgbd_node.cpp @@ -224,7 +224,7 @@ void setTopics() depth_reg_sw_reg_image_rect_raw = "/" + camera + "/" + depth_registered + "/" + DEPTH_REG_SW_REG_IMAGE_RECT_RAW; depth_reg_sw_reg_camera_info = "/" + camera + "/" + depth_registered + "/" + DEPTH_REG_SW_REG_CAMERA_INFO; depth_reg_points = "/" + camera + "/" + depth_registered + "/" + DEPTH_REG_POINTS; - depth_reg_sw_reg_image_rect = "/" + depth_registered + "/" + depth + "/" + DEPTH_REG_SW_REG_IMAGE_RECT; + depth_reg_sw_reg_image_rect = "/" + camera + "/" + depth_registered + "/" + DEPTH_REG_SW_REG_IMAGE_RECT; } int main(int argc, char **argv) From 4b3eb4b0d5c68e25096956f912811afb2ce0a4e7 Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Mon, 28 Mar 2016 17:00:30 -0700 Subject: [PATCH 086/124] 1.0.2 --- camera/CHANGELOG.rst | 18 ++++++++++++++++++ camera/package.xml | 2 +- 2 files changed, 19 insertions(+), 1 deletion(-) diff --git a/camera/CHANGELOG.rst b/camera/CHANGELOG.rst index 7fd84f81ec..f54638fe9d 100644 --- a/camera/CHANGELOG.rst +++ b/camera/CHANGELOG.rst @@ -2,6 +2,24 @@ Changelog for package realsense_camera ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.0.2 (2016-03-28) +------------------ +* Added functionality to access camera using Serial No: + This fixes Issue #18. + Added code to handle various use cases for input serial number such as + --Exit with error if no serial number is specified and multiple cameras are detected. + --Exit with error if no camera is detected that matches the input serial number. + --Prints all the detected cameras. + Updated launch files with a placeholder for serial number. + Updated rgbd_launch test code to remove hardcoded topic names. +* Modified all parameters to lowercase for consistency + This fixes Issue #13. +* Removed support for R200_DISPARITY_MULTIPLIER camera option +* Added missing install targets + This fixes Pull Request #2. + This fixes Issue #17. +* Contributors: Reagan Lopez, Rajvi Jingar + 1.0.1 (2016-03-17) ------------------ * Convert command line args to ROS params diff --git a/camera/package.xml b/camera/package.xml index fc8ed84653..3d8481fa4f 100644 --- a/camera/package.xml +++ b/camera/package.xml @@ -1,7 +1,7 @@ realsense_camera - 1.0.1 + 1.0.2 RealSense Camera package allowing access to Intel 3D cameras and advanced modules Rajvi Jingar From c8b0f89d281fbf0bdb29b1f7573b672cebfbe95f Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Wed, 6 Apr 2016 10:40:55 -0700 Subject: [PATCH 087/124] Updated README and Issue Template with BKC --- .github/ISSUE_TEMPLATE.md | 27 +++++++++++++++------------ camera/README.md | 14 ++++++++------ 2 files changed, 23 insertions(+), 18 deletions(-) diff --git a/.github/ISSUE_TEMPLATE.md b/.github/ISSUE_TEMPLATE.md index 78e8f72d51..152a15757b 100644 --- a/.github/ISSUE_TEMPLATE.md +++ b/.github/ISSUE_TEMPLATE.md @@ -1,23 +1,26 @@ ### System Configuration Please complete Your Configuration detail below. -| Version | Known Good | Your Configuration | -| ---------------- | ------------:| ------------------:| -| Operating System | ubuntu 14.04 | ??? | -| Kernel Version | 4.4.0-13 | ?.?.?-? | -| R200 FW | 1.0.72.06 | ?.?.?.? | -| librealsense | 0.9.1 | ?.?.? | +| Version | Best Known | Your Configuration | +|:---------------- |:---------------------|:---------------------| +| Operating System | Ubuntu 14.04.4 LTS | ? ? ? | +| Kernel | 4.4.0-040400-generic | ?-?-? | +| ROS | indigo | ? | +| librealsense | 0.9.1 | ?.?.? | +| R200 Firmware | 1.0.72.06 | ?.?.?.? | --- #### How to collect Configuration Data -*This section can be delete before submission.* +*This section can be deleted before submission.* | Version | Method | -| ---------------- | ------------ | -| Operating System | `cat /etc/*elease*` | -| Kernel Version | `uname -r` | -| R200 FW | View the ROS log from running node **OR** `/librealsense/bin/cpp-enumerate-devices | grep -i firmware` | -| librealsense | `cat /librealsense/readme.md | grep release-image | awk -F- '{print $3}'` | +|:---------------- |:------------ | +| Operating System | `grep DISTRIB_DESCRIPTION /etc/*elease*` | +| Kernel | `uname -r` | +| ROS | `rosversion -d` | +| librealsense | `cat /librealsense/readme.md | grep release-image | awk -F- '{print $3}'` | +| R200 Firmware | View the ROS log from running nodelet **OR** `/librealsense/bin/cpp-enumerate-devices | grep -i firmware` | + --- diff --git a/camera/README.md b/camera/README.md index d512a13bf5..0fadeee060 100644 --- a/camera/README.md +++ b/camera/README.md @@ -1,6 +1,13 @@ #Intel® RealSense™ Technology - ROS Integration +###Configuration +| Version | Best Known | +|:---------------- |:---------------------| +| Operating System | Ubuntu 14.04.4 LTS | +| Kernel | 4.4.0-040400-generic | +| ROS | indigo | +| librealsense | 0.9.1 | +| R200 Firmware | 1.0.72.06 | -###(ROS Indigo + Ubuntu 14.04 [64-bit]) ###Installation #####Getting the camera to work on Linux @@ -8,10 +15,6 @@ * Make sure that the software stack is installed properly and that the camera is working. This can be checked by connecting the camera to a USB3 port and running the "cpp-capture" sample program in the "librealsense/bin" folder. If this does not work, you should first fix this issue before continuing with the ROS integration. * Make sure "/usr/local/lib" is set in your "LD_LIBRARY_PATH". -* Copy the librealsense header files folder "librealsense/include/librealsense" to "/usr/local/include". - - E.g. sudo cp -r \/include/librealsense /usr/local/include - #####Building package: @@ -75,7 +78,6 @@ Infrared2 camera Stream parameters: serial_no (string, default: blank) Specify the serial_no to uniquely connect to a camera, especially if multiple cameras are detected by the nodelet. - This feature has been tested to work only on kernel version 4.4.0-040400-generic. mode (string, default: preset) Specify the mode to start camera streams. Mode comprises of height, width and fps. Preset mode enables default values whereas Manual mode enables the specified parameter values. From 3297fb3e4e79288105dcd817d9e51183a97b465f Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Fri, 8 Apr 2016 13:34:52 -0700 Subject: [PATCH 088/124] Updated code to enable multi-camera functionality Added code to generate frame_id's based on user entered values. Updated rgbd_launch files to reflect the changes. Updated README to reflect the changes. --- camera/README.md | 40 +++++++++++-------- .../realsense_r200_nodelet.launch.xml | 33 +++++++++------ camera/launch/realsense_r200_rgbd.launch | 16 +++----- camera/src/realsense_camera_nodelet.cpp | 25 +++++++----- camera/src/realsense_camera_nodelet.h | 21 ++++++---- 5 files changed, 81 insertions(+), 54 deletions(-) diff --git a/camera/README.md b/camera/README.md index 0fadeee060..eff13acd79 100644 --- a/camera/README.md +++ b/camera/README.md @@ -72,12 +72,13 @@ Infrared2 camera rosrun tf tf_monitor - #### Static Parameters Stream parameters: serial_no (string, default: blank) Specify the serial_no to uniquely connect to a camera, especially if multiple cameras are detected by the nodelet. + You may get the serial_no from the info stream by launching "realsense_r200_nodelet_standalone_preset.launch" + one at a time for each camera. mode (string, default: preset) Specify the mode to start camera streams. Mode comprises of height, width and fps. Preset mode enables default values whereas Manual mode enables the specified parameter values. @@ -89,7 +90,7 @@ Infrared2 camera Specify the depth camera height resolution. depth_width (int, default: 480) Specify the depth camera width resolution. - depth_fps (int, default: 60) + color_fps (int, default: 60) Specify the color camera FPS depth_fps (int, default: 60) Specify the depth camera FPS @@ -98,7 +99,21 @@ Infrared2 camera enable_pointcloud (bool, default: true) Specify if to enable or not the point cloud camera. enable_tf (bool, default: true) - Specify if to enable or not the transform frames. + Specify if to enable or not the transform frames. + base_frame_id (string, default: camera_link) + Specify the base frame id of the camera. + depth_frame_id (string, default: camera_depth_frame) + Specify the depth frame id of the camera. + color_frame_id (string, default: camera_rgb_frame) + Specify the color frame id of the camera. + depth_optical_frame_id (string, default: camera_depth_optical_frame) + Specify the depth optical frame id of the camera. + color_optical_frame_id (string, default: camera_rgb_optical_frame) + Specify the color optical frame id of the camera. + ir_frame_id (string, default: camera_infrared_frame) + Specify the IR frame id of the camera. + ir2_frame_id (string, default: camera_infrared2_frame) + Specify the IR2 frame id of the camera. camera (string, default: "R200") Specify the camera name. Camera parameters: @@ -206,15 +221,11 @@ For viewing supported camera settings with current values: $ rosservice call /camera/get_settings -Tech and dependencies -* librealsense.so - -System: -* Linux 14.04+ -* ROS Indigo -* R200 (DS4) camera - -** The ROS integration has been tested on a 64bit machine with Linux 14.04 (Trusty) and ROS Indigo. +For running multiple cameras simultaneously: +* Create ".launch" files similar to "realsense_r200_rgbd.launch" for each camera. + * Update the "camera" and "serial_no" arguments with unique values for each camera. + * You may choose to include (or not) the "processing.launch.xml" based on your requirement. +* Launch the ".launch" files for each camera in separate terminals. ###Unit Tests The Unit Tests can be executed using either of the methods: @@ -264,7 +275,4 @@ Hence the launch file "realsense_r200_rgbd.launch" will not generate data for th * /camera/depth_registered/image * /camera/depth/disparity * /camera/depth_registered/disparity - -* If there are multiple R200 cameras connected to a system, the nodelet can be launched for a particular camera -by specifing the serial_no parameter in the launch file. But it has not been tested to launch nodelets simultaneouly for multiple cameras. - +* The performance benchmark for multiple cameras launched at the same time has not been defined yet. diff --git a/camera/launch/includes/realsense_r200_nodelet.launch.xml b/camera/launch/includes/realsense_r200_nodelet.launch.xml index 97f64f3912..dcb94b9a21 100644 --- a/camera/launch/includes/realsense_r200_nodelet.launch.xml +++ b/camera/launch/includes/realsense_r200_nodelet.launch.xml @@ -1,38 +1,47 @@ + - - + - + + + + + + - - - - + + - - + + + - + - - + + + + + + + diff --git a/camera/launch/realsense_r200_rgbd.launch b/camera/launch/realsense_r200_rgbd.launch index e1a51a40a6..c73dabbeae 100644 --- a/camera/launch/realsense_r200_rgbd.launch +++ b/camera/launch/realsense_r200_rgbd.launch @@ -8,9 +8,6 @@ - - - @@ -55,17 +52,16 @@ + - - - - + + - - - + + + diff --git a/camera/src/realsense_camera_nodelet.cpp b/camera/src/realsense_camera_nodelet.cpp index 56f7677cfe..eb0d95771b 100644 --- a/camera/src/realsense_camera_nodelet.cpp +++ b/camera/src/realsense_camera_nodelet.cpp @@ -75,9 +75,6 @@ namespace realsense_camera // Set default configurations. is_device_started_ = false; - frame_id_[RS_STREAM_INFRARED] = IR1_DEF_FRAME; - frame_id_[RS_STREAM_INFRARED2] = IR2_DEF_FRAME; - for (int i = 0; i < STREAM_COUNT; ++i) { camera_info_[i] = NULL; @@ -91,6 +88,11 @@ namespace realsense_camera setStreamOptions(); + frame_id_[RS_STREAM_DEPTH] = depth_optical_frame_id_; + frame_id_[RS_STREAM_COLOR] = color_optical_frame_id_; + frame_id_[RS_STREAM_INFRARED] = ir_frame_id_; + frame_id_[RS_STREAM_INFRARED2] = ir2_frame_id_; + // Advertise the various topics and services. camera_publisher_[RS_STREAM_COLOR] = it.advertiseCamera(COLOR_TOPIC, 1); camera_publisher_[RS_STREAM_DEPTH] = it.advertiseCamera(DEPTH_TOPIC, 1); @@ -581,8 +583,13 @@ namespace realsense_camera pnh_.param("color_height", color_height_, COLOR_HEIGHT); pnh_.param("depth_fps", depth_fps_, DEPTH_FPS); pnh_.param("color_fps", color_fps_, COLOR_FPS); - pnh_.param("depth_frame_id", frame_id_[RS_STREAM_DEPTH], (std::string) DEPTH_OPTICAL_DEF_FRAME); - pnh_.param("rgb_frame_id", frame_id_[RS_STREAM_COLOR], (std::string) COLOR_OPTICAL_DEF_FRAME); + pnh_.param("base_frame_id", base_frame_id_, DEFAULT_BASE_FRAME_ID); + pnh_.param("depth_frame_id", depth_frame_id_, DEFAULT_DEPTH_FRAME_ID); + pnh_.param("color_frame_id", color_frame_id_, DEFAULT_COLOR_FRAME_ID); + pnh_.param("depth_optical_frame_id", depth_optical_frame_id_, DEFAULT_DEPTH_OPTICAL_FRAME_ID); + pnh_.param("color_optical_frame_id", color_optical_frame_id_, DEFAULT_COLOR_OPTICAL_FRAME_ID); + pnh_.param("ir_frame_id", ir_frame_id_, DEFAULT_IR_FRAME_ID); + pnh_.param("ir2_frame_id", ir2_frame_id_, DEFAULT_IR2_FRAME_ID); } /* @@ -928,24 +935,24 @@ namespace realsense_camera // transform base frame to depth frame tr.setOrigin(tf::Vector3(z_extrinsic.translation[0], z_extrinsic.translation[1], z_extrinsic.translation[2])); tr.setRotation(tf::Quaternion(0, 0, 0, 1)); - tf_broadcaster.sendTransform(tf::StampedTransform(tr, time_stamp, BASE_DEF_FRAME, DEPTH_DEF_FRAME)); + tf_broadcaster.sendTransform(tf::StampedTransform(tr, time_stamp, base_frame_id_, depth_frame_id_)); // transform depth frame to depth optical frame tr.setOrigin(tf::Vector3(0,0,0)); q.setEuler( M_PI/2, 0.0, -M_PI/2 ); tr.setRotation( q ); - tf_broadcaster.sendTransform(tf::StampedTransform(tr, time_stamp, DEPTH_DEF_FRAME, frame_id_[RS_STREAM_DEPTH])); + tf_broadcaster.sendTransform(tf::StampedTransform(tr, time_stamp, depth_frame_id_, depth_optical_frame_id_)); // transform base frame to color frame (these are the same) tr.setOrigin(tf::Vector3(0,0,0)); tr.setRotation(tf::Quaternion(0, 0, 0, 1)); - tf_broadcaster.sendTransform(tf::StampedTransform(tr, time_stamp, BASE_DEF_FRAME, COLOR_DEF_FRAME)); + tf_broadcaster.sendTransform(tf::StampedTransform(tr, time_stamp, base_frame_id_, color_frame_id_)); // transform color frame to color optical frame tr.setOrigin(tf::Vector3(0,0,0)); q.setEuler( M_PI/2, 0.0, -M_PI/2 ); tr.setRotation( q ); - tf_broadcaster.sendTransform(tf::StampedTransform(tr, time_stamp, COLOR_DEF_FRAME, frame_id_[RS_STREAM_COLOR])); + tf_broadcaster.sendTransform(tf::StampedTransform(tr, time_stamp, color_frame_id_, color_optical_frame_id_)); sleeper.sleep(); // need sleep or transform won't publish correctly } diff --git a/camera/src/realsense_camera_nodelet.h b/camera/src/realsense_camera_nodelet.h index 0354588d83..3173ce8a69 100644 --- a/camera/src/realsense_camera_nodelet.h +++ b/camera/src/realsense_camera_nodelet.h @@ -91,13 +91,13 @@ class RealsenseNodelet: public nodelet::Nodelet const rs_format COLOR_FORMAT = RS_FORMAT_RGB8; const rs_format IR1_FORMAT = RS_FORMAT_Y8; const rs_format IR2_FORMAT = RS_FORMAT_Y8; - const char *BASE_DEF_FRAME = "camera_link"; - const char *DEPTH_DEF_FRAME = "camera_depth_frame"; - const char *COLOR_DEF_FRAME = "camera_rgb_frame"; - const char *DEPTH_OPTICAL_DEF_FRAME = "camera_depth_optical_frame"; - const char *COLOR_OPTICAL_DEF_FRAME = "camera_rgb_optical_frame"; - const char *IR1_DEF_FRAME = "camera_infrared_optical_frame"; - const char *IR2_DEF_FRAME = "camera_infrared2_optical_frame"; + const std::string DEFAULT_BASE_FRAME_ID = "camera_link"; + const std::string DEFAULT_DEPTH_FRAME_ID = "camera_depth_frame"; + const std::string DEFAULT_COLOR_FRAME_ID = "camera_rgb_frame"; + const std::string DEFAULT_DEPTH_OPTICAL_FRAME_ID = "camera_depth_optical_frame"; + const std::string DEFAULT_COLOR_OPTICAL_FRAME_ID = "camera_rgb_optical_frame"; + const std::string DEFAULT_IR_FRAME_ID = "camera_infrared_frame"; + const std::string DEFAULT_IR2_FRAME_ID = "camera_infrared2_frame"; const char *DEPTH_TOPIC = "camera/depth/image_raw"; const char *COLOR_TOPIC = "camera/color/image_raw"; const char *IR1_TOPIC = "camera/infrared1/image_raw"; @@ -130,6 +130,13 @@ class RealsenseNodelet: public nodelet::Nodelet bool enable_depth_; bool enable_pointcloud_; bool enable_tf_; + std::string base_frame_id_; + std::string depth_frame_id_; + std::string color_frame_id_; + std::string depth_optical_frame_id_; + std::string color_optical_frame_id_; + std::string ir_frame_id_; + std::string ir2_frame_id_; std::string camera_ = "R200"; const uint16_t *image_depth16_; From 62b19add0c488f683060cf822161e47eeadd67ce Mon Sep 17 00:00:00 2001 From: Mark D Horn Date: Mon, 18 Apr 2016 12:44:30 -0700 Subject: [PATCH 089/124] Add Project Contribution Conditions --- .github/CONTRIBUTING.md | 75 ++++++++++++++++++++++++++++++++ .github/PULL_REQUEST_TEMPLATE.md | 2 + README.md | 30 ++++++++++++- 3 files changed, 106 insertions(+), 1 deletion(-) create mode 100644 .github/CONTRIBUTING.md diff --git a/.github/CONTRIBUTING.md b/.github/CONTRIBUTING.md new file mode 100644 index 0000000000..335ca26f3b --- /dev/null +++ b/.github/CONTRIBUTING.md @@ -0,0 +1,75 @@ +# Contributing to ROS RealSense™ Project + +Third-party patches and contributions are welcome. We do require +you read and agree to the Contribution License Agreement below. + +## Contribution License Agreement + +The Intel® RealSense™ ROS Project is developed and distributed under +a BSD license as noted in [camera/licenses/License.txt](../camera/licenses/License.txt). + +By making a contribution to this project, I certify that: + +(a) The contribution was created in whole or in part by me and I +have the right to submit it under the open source license +indicated in the file; or + +(b) The contribution is based upon previous work that, to the best +of my knowledge, is covered under an appropriate open source +license and I have the right under that license to submit that +work with modifications, whether created in whole or in part +by me, under the same open source license (unless I am +permitted to submit under a different license), as indicated +in the file; or + +(c) The contribution was provided directly to me by some other +person who certified (a), (b) or (c) and I have not modified +it. + +(d) I understand and agree that this project and the contribution +are public and that a record of the contribution (including all +personal information I submit with it, including my sign-off) is +maintained indefinitely and may be redistributed consistent with +this project or the open source license(s) involved. + +# Contribution Prerequisites + +* Create a [GitHub account](https://github.com/join) if you do not already have one. +* Search the existing [GitHub Issues](../../../issues) +to see if your contribution is already documented. + * Submit a [new GitHub Issue](../../../issues/new) if one does not exist. + * Complete the provided template with your system configuration. + * For Bug fixes, include directions on how to reproduce the problem. + * For new functionality or features, please describe in detail the requirements. +* [Create a Fork](../../../fork) of the repository on GitHub for your contribution. + +# Submitting Changes + +* Create a Topic branch for your work. + * Base the topic branch on the ROS development branch `-devel`. +* Ensure changes follow the [ROS coding Style Guide](http://wiki.ros.org/StyleGuide) +* Each commit needs to be functional/compile by itself. +* Follow [Git Commit Guidelines](https://git-scm.com/book/ch5-2.html#Commit-Guidelines) +regarding commit formatting. + * Check for unnecessary whitespace with `git diff --check` before committing. +* Rebase commits to squash where appropriate. +* Verify the Test cases found in the package 'test' directory are passing. + * Changes with new functionality should include new test cases. +* Submit a [Pull Request](../../../compare) to the repository. + * Ensure that it is flagged as "Able to merge", if not you may need to rebase your Fork. + * List the Issues fixed by the Pull Request. + +### Monitor Your Pull Request + +* The maintainers attempt to review all Pull Requests in a timely manner; worse case +is once per week. +* If maintainers request changes or additional information for your Pull Request, the +expectation is the submitter replies within two weeks. +* Pull Requests may be closed without being merged if there is no submitter response after 3+ weeks. + +# Contribution Resources + +* [Create a GitHub account](https://github.com/join) +* [GitHub Pull Request documentation](https://help.github.com/articles/using-pull-requests) +* [ROS coding Style Guide](http://wiki.ros.org/StyleGuide) +* [Git Commit Guidelines](https://git-scm.com/book/ch5-2.html#Commit-Guidelines) diff --git a/.github/PULL_REQUEST_TEMPLATE.md b/.github/PULL_REQUEST_TEMPLATE.md index e0ebfd2a0d..b41bd2c73e 100644 --- a/.github/PULL_REQUEST_TEMPLATE.md +++ b/.github/PULL_REQUEST_TEMPLATE.md @@ -1,3 +1,5 @@ +**Please ensure the above *guidelines for contributing* are met.** + Fixes Issue: # Changes proposed in this pull request: diff --git a/README.md b/README.md index 610271fd88..869cf83142 100644 --- a/README.md +++ b/README.md @@ -5,5 +5,33 @@ www.intel.com/realsense www.ros.org - Refer to the README.md file within each package for more details. + +# Contributing to the Project + +The Intel® RealSense™ ROS Project is developed and distributed under +a BSD license as noted in [camera/licenses/License.txt](camera/licenses/License.txt). + +By making a contribution to this project, I certify that: + +(a) The contribution was created in whole or in part by me and I +have the right to submit it under the open source license +indicated in the file; or + +(b) The contribution is based upon previous work that, to the best +of my knowledge, is covered under an appropriate open source +license and I have the right under that license to submit that +work with modifications, whether created in whole or in part +by me, under the same open source license (unless I am +permitted to submit under a different license), as indicated +in the file; or + +(c) The contribution was provided directly to me by some other +person who certified (a), (b) or (c) and I have not modified +it. + +(d) I understand and agree that this project and the contribution +are public and that a record of the contribution (including all +personal information I submit with it, including my sign-off) is +maintained indefinitely and may be redistributed consistent with +this project or the open source license(s) involved. From a3f0ed5654055d0e42bb564d27d0b5581fd542f9 Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Fri, 22 Apr 2016 14:42:27 -0700 Subject: [PATCH 090/124] Modified variable names to match ROS standards --- camera/src/realsense_camera_nodelet.cpp | 8 ++++---- camera/src/realsense_camera_nodelet.h | 4 ++-- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/camera/src/realsense_camera_nodelet.cpp b/camera/src/realsense_camera_nodelet.cpp index eb0d95771b..51336de453 100644 --- a/camera/src/realsense_camera_nodelet.cpp +++ b/camera/src/realsense_camera_nodelet.cpp @@ -443,7 +443,7 @@ namespace realsense_camera { for (int i = 0; i < RS_OPTION_COUNT; ++i) { - option_str o = { (rs_option) i }; + CameraOptions o = { (rs_option) i }; if (rs_device_supports_option(rs_device_, o.opt, &rs_error_)) { @@ -452,7 +452,7 @@ namespace realsense_camera if (o.min != o.max) { o.value = rs_get_device_option(rs_device_, o.opt, 0); - options.push_back(o); + camera_options_.push_back(o); } } } @@ -552,7 +552,7 @@ namespace realsense_camera std::string get_options_result_str; std::string opt_name, opt_value; - for (option_str o: options) + for (CameraOptions o: camera_options_) { opt_name = rs_option_to_string(o.opt); std::transform(opt_name.begin(), opt_name.end(), opt_name.begin(), ::tolower); @@ -603,7 +603,7 @@ namespace realsense_camera std::vector param_desc = params_config.__getParamDescriptions__(); // Iterate through the supported camera options - for (option_str o: options) + for (CameraOptions o: camera_options_) { std::string opt_name = rs_option_to_string(o.opt); bool found = false; diff --git a/camera/src/realsense_camera_nodelet.h b/camera/src/realsense_camera_nodelet.h index 3173ce8a69..909b5b175e 100644 --- a/camera/src/realsense_camera_nodelet.h +++ b/camera/src/realsense_camera_nodelet.h @@ -165,12 +165,12 @@ class RealsenseNodelet: public nodelet::Nodelet std::map config_; int stream_step_[STREAM_COUNT]; - struct option_str + struct CameraOptions { rs_option opt; double min, max, step, value; }; - std::vector options; + std::vector camera_options_; boost::shared_ptr> dynamic_reconf_server_; // Member Functions. From 64d048c510e5a4f22a580aba852d60a151bf216b Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Fri, 22 Apr 2016 18:23:06 -0700 Subject: [PATCH 091/124] Updated Issue Template with Backend and ROS RealSense details --- .github/ISSUE_TEMPLATE.md | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/.github/ISSUE_TEMPLATE.md b/.github/ISSUE_TEMPLATE.md index 152a15757b..e77dce1283 100644 --- a/.github/ISSUE_TEMPLATE.md +++ b/.github/ISSUE_TEMPLATE.md @@ -5,7 +5,9 @@ Please complete Your Configuration detail below. |:---------------- |:---------------------|:---------------------| | Operating System | Ubuntu 14.04.4 LTS | ? ? ? | | Kernel | 4.4.0-040400-generic | ?-?-? | +| Backend | video4linux | ? | | ROS | indigo | ? | +| ROS RealSense | Latest Release | ?.?.? | | librealsense | 0.9.1 | ?.?.? | | R200 Firmware | 1.0.72.06 | ?.?.?.? | @@ -17,7 +19,9 @@ Please complete Your Configuration detail below. |:---------------- |:------------ | | Operating System | `grep DISTRIB_DESCRIPTION /etc/*elease*` | | Kernel | `uname -r` | +| Backend | `ls /sys/class | grep video4linux` | | ROS | `rosversion -d` | +| ROS RealSense | `rosversion realsense_camera` | | librealsense | `cat /librealsense/readme.md | grep release-image | awk -F- '{print $3}'` | | R200 Firmware | View the ROS log from running nodelet **OR** `/librealsense/bin/cpp-enumerate-devices | grep -i firmware` | From 7328f109c7584c3a6599d70471a09cbfb103c825 Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Fri, 22 Apr 2016 18:33:54 -0700 Subject: [PATCH 092/124] Updated README with Backend details --- camera/README.md | 1 + 1 file changed, 1 insertion(+) diff --git a/camera/README.md b/camera/README.md index eff13acd79..baa95acd7b 100644 --- a/camera/README.md +++ b/camera/README.md @@ -4,6 +4,7 @@ |:---------------- |:---------------------| | Operating System | Ubuntu 14.04.4 LTS | | Kernel | 4.4.0-040400-generic | +| Backend | video4linux | | ROS | indigo | | librealsense | 0.9.1 | | R200 Firmware | 1.0.72.06 | From b7e04b4aa710b17eae39595f45519831088c9047 Mon Sep 17 00:00:00 2001 From: Mark D Horn Date: Fri, 22 Apr 2016 17:55:44 -0700 Subject: [PATCH 093/124] Updated RGBD Launch File for Manual Mode Depth point cloud does not work at 60 fps; dropped to 30 fps. --- camera/README.md | 7 ++++- .../realsense_r200_nodelet.launch.xml | 12 +++++++++ camera/launch/realsense_r200_rgbd.launch | 27 +++++++++++++++---- 3 files changed, 40 insertions(+), 6 deletions(-) diff --git a/camera/README.md b/camera/README.md index baa95acd7b..f5d92f7705 100644 --- a/camera/README.md +++ b/camera/README.md @@ -268,12 +268,17 @@ Refer to the function definitions in [realsense_camera_nodelet.h](src/realsense_ * Depth stream: Y16 * Infrared stream: Y8 +* Generating a Depth Registered Point Cloud is very memory intensive. +The topic /camera/depth_registered/points, generated by launch file +"realsense_r200_rgbd.launch", works best at 30 fps using 640x480 resolution +on a system with 16GB of RAM. + * The camera does not provide hardware based depth registration/projector data. Hence the launch file "realsense_r200_rgbd.launch" will not generate data for the following topics: * /camera/depth_registered/hw_registered/image_rect_raw - * /camera/depth_registered/points * /camera/depth_registered/hw_registered/image_rect * /camera/depth_registered/image * /camera/depth/disparity * /camera/depth_registered/disparity + * The performance benchmark for multiple cameras launched at the same time has not been defined yet. diff --git a/camera/launch/includes/realsense_r200_nodelet.launch.xml b/camera/launch/includes/realsense_r200_nodelet.launch.xml index dcb94b9a21..1d9eb43e70 100644 --- a/camera/launch/includes/realsense_r200_nodelet.launch.xml +++ b/camera/launch/includes/realsense_r200_nodelet.launch.xml @@ -15,6 +15,12 @@ + + + + + + + + + + + + + + + - - + + @@ -28,7 +37,7 @@ - + @@ -36,11 +45,12 @@ - + + @@ -57,11 +67,18 @@ - + + + + + + + + From 51520314d28ee3f4a18621bf4d270c6f6b073f2d Mon Sep 17 00:00:00 2001 From: rjingar Date: Sun, 8 May 2016 14:07:20 -0700 Subject: [PATCH 094/124] Added unit test to check camera_info distortion-parameter --- camera/test/realsense_camera_test_node.cpp | 14 ++++++++++++++ camera/test/realsense_camera_test_node.h | 1 + 2 files changed, 15 insertions(+) diff --git a/camera/test/realsense_camera_test_node.cpp b/camera/test/realsense_camera_test_node.cpp index ed4f451586..1380b27665 100644 --- a/camera/test/realsense_camera_test_node.cpp +++ b/camera/test/realsense_camera_test_node.cpp @@ -229,6 +229,11 @@ void imageColorCallback(const sensor_msgs::ImageConstPtr & msg, const sensor_msg color_caminfo_projection_recv[i] = info_msg->P[i]; } + for (unsigned int i = 0; i < 5; i++) + { + color_caminfo_D_recv[i] = info_msg->D[i]; + } + color_recv = true; } @@ -297,6 +302,15 @@ TEST (RealsenseTests, testColorCameraInfo) EXPECT_TRUE(color_caminfo_projection_recv[10] != (double) 0); EXPECT_EQ(color_caminfo_projection_recv[11], (double) 0); + float color_caminfo_D = 1; + // ignoring the 5th value since it always appears to be 0.0 on tested R200 cameras + for (unsigned int i = 0; i < 4; i++) + { + color_caminfo_D = color_caminfo_D && color_caminfo_D_recv[i]; + } + + EXPECT_TRUE(color_caminfo_D != (float) 0); + } } diff --git a/camera/test/realsense_camera_test_node.h b/camera/test/realsense_camera_test_node.h index df3cc4049a..89ab0116bc 100644 --- a/camera/test/realsense_camera_test_node.h +++ b/camera/test/realsense_camera_test_node.h @@ -132,6 +132,7 @@ int color_caminfo_height_recv = 0; int color_caminfo_width_recv = 0; double color_caminfo_rotation_recv[9] = {0}; double color_caminfo_projection_recv[12] = {0}; +float color_caminfo_D_recv[5] = {0}; int inf1_caminfo_height_recv = 0; int inf1_caminfo_width_recv = 0; double inf1_caminfo_rotation_recv[9] = {0}; From 9515bca5916bda676d7cca934aa91a0c97fb1d13 Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Fri, 6 May 2016 14:57:08 -0700 Subject: [PATCH 095/124] Fixed unit conversion bug in the projection matrix The unit of measure in librealsense is meters. Hence mm to meter conversion is not required. --- camera/src/realsense_camera_nodelet.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/camera/src/realsense_camera_nodelet.cpp b/camera/src/realsense_camera_nodelet.cpp index 51336de453..50a424e6a1 100644 --- a/camera/src/realsense_camera_nodelet.cpp +++ b/camera/src/realsense_camera_nodelet.cpp @@ -519,9 +519,9 @@ namespace realsense_camera rs_extrinsics z_extrinsic; rs_get_device_extrinsics(rs_device_, RS_STREAM_DEPTH, RS_STREAM_COLOR, &z_extrinsic, &rs_error_); checkError(); - camera_info_[stream_index]->P.at(3) = z_extrinsic.translation[0]/1000; // Tx - camera_info_[stream_index]->P.at(7) = z_extrinsic.translation[1]/1000; // Ty - camera_info_[stream_index]->P.at(11) = z_extrinsic.translation[2]/1000; // Tz + camera_info_[stream_index]->P.at(3) = z_extrinsic.translation[0]; // Tx + camera_info_[stream_index]->P.at(7) = z_extrinsic.translation[1]; // Ty + camera_info_[stream_index]->P.at(11) = z_extrinsic.translation[2]; // Tz } camera_info_[stream_index]->distortion_model = "plumb_bob"; From a72c362caadabd2e08c5713eed06533ff99cb7a4 Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Fri, 6 May 2016 16:13:28 -0700 Subject: [PATCH 096/124] Fixed README bug to show correct depth format Z16 --- camera/README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/camera/README.md b/camera/README.md index f5d92f7705..6bf71a854f 100644 --- a/camera/README.md +++ b/camera/README.md @@ -265,7 +265,7 @@ Refer to the function definitions in [realsense_camera_nodelet.h](src/realsense_ * Currently, the camera nodelet only supports the following formats: * Color stream: RGB8 - * Depth stream: Y16 + * Depth stream: Z16 * Infrared stream: Y8 * Generating a Depth Registered Point Cloud is very memory intensive. From 126764bd50974ef44946521b81bd8594e31e9e45 Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Thu, 19 May 2016 17:31:39 -0700 Subject: [PATCH 097/124] Added nodelet name to log messages --- camera/src/realsense_camera_nodelet.cpp | 55 +++++++++++++------------ camera/src/realsense_camera_nodelet.h | 1 + 2 files changed, 29 insertions(+), 27 deletions(-) diff --git a/camera/src/realsense_camera_nodelet.cpp b/camera/src/realsense_camera_nodelet.cpp index 2475c668e9..8925e775fa 100644 --- a/camera/src/realsense_camera_nodelet.cpp +++ b/camera/src/realsense_camera_nodelet.cpp @@ -61,7 +61,7 @@ namespace realsense_camera checkError(); } - ROS_INFO_STREAM ("RealSense Camera - Stopping camera nodelet."); + ROS_INFO_STREAM (nodelet_name_ << " - Stopping camera nodelet."); ros::shutdown(); } @@ -70,7 +70,8 @@ namespace realsense_camera */ void RealsenseNodelet::onInit() { - ROS_INFO_STREAM ("RealSense Camera - Starting camera nodelet."); + nodelet_name_ = getName(); // Get the nodelet name + ROS_INFO_STREAM (nodelet_name_ << " - Starting camera nodelet."); // Set default configurations. is_device_started_ = false; @@ -142,13 +143,13 @@ namespace realsense_camera // Enable streams. if (mode_.compare ("manual") == 0) { - ROS_INFO_STREAM ("RealSense Camera - Enabling Color Stream: manual mode"); + ROS_INFO_STREAM (nodelet_name_ << " - Enabling Color Stream: manual mode"); rs_enable_stream(rs_device_, RS_STREAM_COLOR, color_width_, color_height_, COLOR_FORMAT, color_fps_, &rs_error_); checkError(); } else { - ROS_INFO_STREAM ("RealSense Camera - Enabling Color Stream: preset mode"); + ROS_INFO_STREAM (nodelet_name_ << " - Enabling Color Stream: preset mode"); rs_enable_stream_preset(rs_device_, RS_STREAM_COLOR, RS_PRESET_BEST_QUALITY, &rs_error_); checkError(); } @@ -165,13 +166,13 @@ namespace realsense_camera // Enable streams. if (mode_.compare ("manual") == 0) { - ROS_INFO_STREAM ("RealSense Camera - Enabling Depth Stream: manual mode"); + ROS_INFO_STREAM (nodelet_name_ << " - Enabling Depth Stream: manual mode"); rs_enable_stream(rs_device_, RS_STREAM_DEPTH, depth_width_, depth_height_, DEPTH_FORMAT, depth_fps_, &rs_error_); checkError(); } else { - ROS_INFO_STREAM ("RealSense Camera - Enabling Depth Stream: preset mode"); + ROS_INFO_STREAM (nodelet_name_ << " - Enabling Depth Stream: preset mode"); rs_enable_stream_preset(rs_device_, RS_STREAM_DEPTH, RS_PRESET_BEST_QUALITY, &rs_error_); checkError(); } @@ -188,13 +189,13 @@ namespace realsense_camera // Enable streams. if (mode_.compare ("manual") == 0) { - ROS_INFO_STREAM ("RealSense Camera - Enabling Infrared Stream: manual mode"); + ROS_INFO_STREAM (nodelet_name_ << " - Enabling Infrared Stream: manual mode"); rs_enable_stream(rs_device_, RS_STREAM_INFRARED, depth_width_, depth_height_, IR1_FORMAT, depth_fps_, &rs_error_); checkError(); } else { - ROS_INFO_STREAM ("RealSense Camera - Enabling Infrared Stream: preset mode"); + ROS_INFO_STREAM (nodelet_name_ << " - Enabling Infrared Stream: preset mode"); rs_enable_stream_preset(rs_device_, RS_STREAM_INFRARED, RS_PRESET_BEST_QUALITY, &rs_error_); checkError(); } @@ -211,12 +212,12 @@ namespace realsense_camera // Enable streams. if (mode_.compare ("manual") == 0) { - ROS_INFO_STREAM ("RealSense Camera - Enabling Infrared2 Stream: manual mode"); + ROS_INFO_STREAM (nodelet_name_ << " - Enabling Infrared2 Stream: manual mode"); rs_enable_stream(rs_device_, RS_STREAM_INFRARED2, depth_width_, depth_height_, IR2_FORMAT, depth_fps_, 0); } else { - ROS_INFO_STREAM ("RealSense Camera - Enabling Infrared2 Stream: preset mode"); + ROS_INFO_STREAM (nodelet_name_ << " - Enabling Infrared2 Stream: preset mode"); rs_enable_stream_preset(rs_device_, RS_STREAM_INFRARED2, RS_PRESET_BEST_QUALITY, 0); } @@ -287,7 +288,7 @@ namespace realsense_camera { if (enable_color_ == false) { - ROS_INFO_STREAM ("RealSense Camera - Color stream is also disabled. Cannot disable depth stream"); + ROS_INFO_STREAM (nodelet_name_ << " - Color stream is also disabled. Cannot disable depth stream"); config.enable_depth = true; } else @@ -305,7 +306,7 @@ namespace realsense_camera { if (rs_error_) { - ROS_ERROR_STREAM ("RealSense Camera - Error calling " << rs_get_failed_function(rs_error_) << " ( " + ROS_ERROR_STREAM (nodelet_name_ << " - Error calling " << rs_get_failed_function(rs_error_) << " ( " << rs_get_failed_args(rs_error_) << " ): \n" << rs_get_error_message(rs_error_) << " \n"); rs_free_error(rs_error_); @@ -330,7 +331,7 @@ namespace realsense_camera { if (enable_depth_ == false && enable_color_ == false) { - ROS_ERROR_STREAM("RealSense Camera - None of the streams are enabled. Exiting."); + ROS_ERROR_STREAM(nodelet_name_ << " - None of the streams are enabled. Exiting."); return false; } @@ -343,12 +344,12 @@ namespace realsense_camera // Exit with error if no cameras are connected. if (num_of_cameras_ < 1) { - ROS_ERROR_STREAM("RealSense Camera - No cameras detected. Exiting!"); + ROS_ERROR_STREAM(nodelet_name_ << " - No cameras detected. Exiting!"); return false; } rs_device_ = getCameraBySerialNumber(); // Get rs_device_ using input serial number. - std::string detected_camera_msg = "RealSense Camera - Detected following cameras:"; + std::string detected_camera_msg = nodelet_name_ + " - Detected following cameras:"; for (rs_device *rs_detected_device: rs_detected_devices_) { detected_camera_msg = detected_camera_msg + @@ -362,14 +363,14 @@ namespace realsense_camera // Exit with error if no serial number is specified and multiple cameras are detected. if ((serial_no_.empty() == true) && (num_of_cameras_ > 1)) { - ROS_ERROR_STREAM("RealSense Camera - Multiple cameras detected but no input serial_no specified. Exiting!"); + ROS_ERROR_STREAM(nodelet_name_ << " - Multiple cameras detected but no input serial_no specified. Exiting!"); return false; } // Exit with error if no camera is detected that matches the input serial number. if ((serial_no_.empty() != true) && (rs_device_ == NULL)) { - ROS_ERROR_STREAM("RealSense Camera - No camera detected with input serial_no = " << serial_no_ << ". Exiting!"); + ROS_ERROR_STREAM(nodelet_name_ << " - No camera detected with input serial_no = " << serial_no_ << ". Exiting!"); return false; } @@ -381,7 +382,7 @@ namespace realsense_camera checkError(); } - ROS_INFO_STREAM("RealSense Camera - Connecting to camera with Serial No: " << + ROS_INFO_STREAM(nodelet_name_ << " - Connecting to camera with Serial No: " << rs_get_device_serial(rs_device_, &rs_error_)); checkError(); @@ -642,7 +643,7 @@ namespace realsense_camera { opt_val = val; } - ROS_INFO_STREAM ("RealSense Camera - Static Options: " << opt_name << " = " << opt_val); + ROS_INFO_STREAM (nodelet_name_ << " - Static Options: " << opt_name << " = " << opt_val); rs_set_device_option(rs_device_, o.opt, opt_val, &rs_error_); checkError(); } @@ -704,28 +705,28 @@ namespace realsense_camera { rs_stop_device(rs_device_, &rs_error_); checkError(); - ROS_INFO_STREAM ("RealSense Camera - Device Stopped"); + ROS_INFO_STREAM (nodelet_name_ << " - Device Stopped"); } //disable depth, infrared1 and infrared2 streams rs_disable_stream(rs_device_, RS_STREAM_DEPTH, &rs_error_); checkError(); - ROS_INFO_STREAM ("RealSense Camera - Depth Stream Disabled"); + ROS_INFO_STREAM (nodelet_name_ << " - Depth Stream Disabled"); rs_disable_stream(rs_device_, RS_STREAM_INFRARED, &rs_error_); checkError(); - ROS_INFO_STREAM ("RealSense Camera - Infrared1 stream Disabled"); + ROS_INFO_STREAM (nodelet_name_ << " - Infrared1 stream Disabled"); rs_disable_stream(rs_device_, RS_STREAM_INFRARED2, &rs_error_); checkError(); - ROS_INFO_STREAM ("RealSense Camera - Infrared2 stream Disabled"); + ROS_INFO_STREAM (nodelet_name_ << " - Infrared2 stream Disabled"); if (rs_is_device_streaming(rs_device_, 0) == 0) { rs_start_device(rs_device_, &rs_error_); checkError(); - ROS_INFO_STREAM ("RealSense Camera - Device Started"); + ROS_INFO_STREAM (nodelet_name_ << " - Device Started"); } } @@ -735,7 +736,7 @@ namespace realsense_camera { rs_stop_device(rs_device_, &rs_error_); checkError(); - ROS_INFO_STREAM ("RealSense Camera - Device Stopped"); + ROS_INFO_STREAM (nodelet_name_ << " - Device Stopped"); } enableDepthStream(); @@ -746,7 +747,7 @@ namespace realsense_camera { rs_start_device(rs_device_, &rs_error_); checkError(); - ROS_INFO_STREAM ("RealSense Camera - Device Started"); + ROS_INFO_STREAM (nodelet_name_ << " - Device Started"); } } @@ -915,7 +916,7 @@ namespace realsense_camera void RealsenseNodelet::publishTransforms() { // publish transforms for the cameras - ROS_INFO_STREAM("RealSense Camera - Publishing camera transforms"); + ROS_INFO_STREAM(nodelet_name_ << " - Publishing camera transforms"); tf::Transform tr; tf::Quaternion q; tf::TransformBroadcaster tf_broadcaster; diff --git a/camera/src/realsense_camera_nodelet.h b/camera/src/realsense_camera_nodelet.h index 909b5b175e..3cee0d2bfd 100644 --- a/camera/src/realsense_camera_nodelet.h +++ b/camera/src/realsense_camera_nodelet.h @@ -138,6 +138,7 @@ class RealsenseNodelet: public nodelet::Nodelet std::string ir_frame_id_; std::string ir2_frame_id_; std::string camera_ = "R200"; + std::string nodelet_name_; const uint16_t *image_depth16_; cv::Mat image_[STREAM_COUNT]; From 0c7606716a63fcbcfece09d8071cef7dfbce0388 Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Thu, 19 May 2016 17:35:08 -0700 Subject: [PATCH 098/124] Removed extra space before ROS Log function calls --- camera/src/realsense_camera_nodelet.cpp | 40 ++++++++++++------------- 1 file changed, 20 insertions(+), 20 deletions(-) diff --git a/camera/src/realsense_camera_nodelet.cpp b/camera/src/realsense_camera_nodelet.cpp index 8925e775fa..3a0e283855 100644 --- a/camera/src/realsense_camera_nodelet.cpp +++ b/camera/src/realsense_camera_nodelet.cpp @@ -61,7 +61,7 @@ namespace realsense_camera checkError(); } - ROS_INFO_STREAM (nodelet_name_ << " - Stopping camera nodelet."); + ROS_INFO_STREAM(nodelet_name_ << " - Stopping camera nodelet."); ros::shutdown(); } @@ -71,7 +71,7 @@ namespace realsense_camera void RealsenseNodelet::onInit() { nodelet_name_ = getName(); // Get the nodelet name - ROS_INFO_STREAM (nodelet_name_ << " - Starting camera nodelet."); + ROS_INFO_STREAM(nodelet_name_ << " - Starting camera nodelet."); // Set default configurations. is_device_started_ = false; @@ -143,13 +143,13 @@ namespace realsense_camera // Enable streams. if (mode_.compare ("manual") == 0) { - ROS_INFO_STREAM (nodelet_name_ << " - Enabling Color Stream: manual mode"); + ROS_INFO_STREAM(nodelet_name_ << " - Enabling Color Stream: manual mode"); rs_enable_stream(rs_device_, RS_STREAM_COLOR, color_width_, color_height_, COLOR_FORMAT, color_fps_, &rs_error_); checkError(); } else { - ROS_INFO_STREAM (nodelet_name_ << " - Enabling Color Stream: preset mode"); + ROS_INFO_STREAM(nodelet_name_ << " - Enabling Color Stream: preset mode"); rs_enable_stream_preset(rs_device_, RS_STREAM_COLOR, RS_PRESET_BEST_QUALITY, &rs_error_); checkError(); } @@ -166,13 +166,13 @@ namespace realsense_camera // Enable streams. if (mode_.compare ("manual") == 0) { - ROS_INFO_STREAM (nodelet_name_ << " - Enabling Depth Stream: manual mode"); + ROS_INFO_STREAM(nodelet_name_ << " - Enabling Depth Stream: manual mode"); rs_enable_stream(rs_device_, RS_STREAM_DEPTH, depth_width_, depth_height_, DEPTH_FORMAT, depth_fps_, &rs_error_); checkError(); } else { - ROS_INFO_STREAM (nodelet_name_ << " - Enabling Depth Stream: preset mode"); + ROS_INFO_STREAM(nodelet_name_ << " - Enabling Depth Stream: preset mode"); rs_enable_stream_preset(rs_device_, RS_STREAM_DEPTH, RS_PRESET_BEST_QUALITY, &rs_error_); checkError(); } @@ -189,13 +189,13 @@ namespace realsense_camera // Enable streams. if (mode_.compare ("manual") == 0) { - ROS_INFO_STREAM (nodelet_name_ << " - Enabling Infrared Stream: manual mode"); + ROS_INFO_STREAM(nodelet_name_ << " - Enabling Infrared Stream: manual mode"); rs_enable_stream(rs_device_, RS_STREAM_INFRARED, depth_width_, depth_height_, IR1_FORMAT, depth_fps_, &rs_error_); checkError(); } else { - ROS_INFO_STREAM (nodelet_name_ << " - Enabling Infrared Stream: preset mode"); + ROS_INFO_STREAM(nodelet_name_ << " - Enabling Infrared Stream: preset mode"); rs_enable_stream_preset(rs_device_, RS_STREAM_INFRARED, RS_PRESET_BEST_QUALITY, &rs_error_); checkError(); } @@ -212,12 +212,12 @@ namespace realsense_camera // Enable streams. if (mode_.compare ("manual") == 0) { - ROS_INFO_STREAM (nodelet_name_ << " - Enabling Infrared2 Stream: manual mode"); + ROS_INFO_STREAM(nodelet_name_ << " - Enabling Infrared2 Stream: manual mode"); rs_enable_stream(rs_device_, RS_STREAM_INFRARED2, depth_width_, depth_height_, IR2_FORMAT, depth_fps_, 0); } else { - ROS_INFO_STREAM (nodelet_name_ << " - Enabling Infrared2 Stream: preset mode"); + ROS_INFO_STREAM(nodelet_name_ << " - Enabling Infrared2 Stream: preset mode"); rs_enable_stream_preset(rs_device_, RS_STREAM_INFRARED2, RS_PRESET_BEST_QUALITY, 0); } @@ -288,7 +288,7 @@ namespace realsense_camera { if (enable_color_ == false) { - ROS_INFO_STREAM (nodelet_name_ << " - Color stream is also disabled. Cannot disable depth stream"); + ROS_INFO_STREAM(nodelet_name_ << " - Color stream is also disabled. Cannot disable depth stream"); config.enable_depth = true; } else @@ -306,7 +306,7 @@ namespace realsense_camera { if (rs_error_) { - ROS_ERROR_STREAM (nodelet_name_ << " - Error calling " << rs_get_failed_function(rs_error_) << " ( " + ROS_ERROR_STREAM(nodelet_name_ << " - Error calling " << rs_get_failed_function(rs_error_) << " ( " << rs_get_failed_args(rs_error_) << " ): \n" << rs_get_error_message(rs_error_) << " \n"); rs_free_error(rs_error_); @@ -643,7 +643,7 @@ namespace realsense_camera { opt_val = val; } - ROS_INFO_STREAM (nodelet_name_ << " - Static Options: " << opt_name << " = " << opt_val); + ROS_INFO_STREAM(nodelet_name_ << " - Static Options: " << opt_name << " = " << opt_val); rs_set_device_option(rs_device_, o.opt, opt_val, &rs_error_); checkError(); } @@ -705,28 +705,28 @@ namespace realsense_camera { rs_stop_device(rs_device_, &rs_error_); checkError(); - ROS_INFO_STREAM (nodelet_name_ << " - Device Stopped"); + ROS_INFO_STREAM(nodelet_name_ << " - Device Stopped"); } //disable depth, infrared1 and infrared2 streams rs_disable_stream(rs_device_, RS_STREAM_DEPTH, &rs_error_); checkError(); - ROS_INFO_STREAM (nodelet_name_ << " - Depth Stream Disabled"); + ROS_INFO_STREAM(nodelet_name_ << " - Depth Stream Disabled"); rs_disable_stream(rs_device_, RS_STREAM_INFRARED, &rs_error_); checkError(); - ROS_INFO_STREAM (nodelet_name_ << " - Infrared1 stream Disabled"); + ROS_INFO_STREAM(nodelet_name_ << " - Infrared1 stream Disabled"); rs_disable_stream(rs_device_, RS_STREAM_INFRARED2, &rs_error_); checkError(); - ROS_INFO_STREAM (nodelet_name_ << " - Infrared2 stream Disabled"); + ROS_INFO_STREAM(nodelet_name_ << " - Infrared2 stream Disabled"); if (rs_is_device_streaming(rs_device_, 0) == 0) { rs_start_device(rs_device_, &rs_error_); checkError(); - ROS_INFO_STREAM (nodelet_name_ << " - Device Started"); + ROS_INFO_STREAM(nodelet_name_ << " - Device Started"); } } @@ -736,7 +736,7 @@ namespace realsense_camera { rs_stop_device(rs_device_, &rs_error_); checkError(); - ROS_INFO_STREAM (nodelet_name_ << " - Device Stopped"); + ROS_INFO_STREAM(nodelet_name_ << " - Device Stopped"); } enableDepthStream(); @@ -747,7 +747,7 @@ namespace realsense_camera { rs_start_device(rs_device_, &rs_error_); checkError(); - ROS_INFO_STREAM (nodelet_name_ << " - Device Started"); + ROS_INFO_STREAM(nodelet_name_ << " - Device Started"); } } From 348652d57c674f8bf173ccb91185cf1c5445d101 Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Thu, 19 May 2016 17:51:30 -0700 Subject: [PATCH 099/124] Refined the log messages and made them consistent --- camera/src/realsense_camera_nodelet.cpp | 38 +++++++++++++------------ 1 file changed, 20 insertions(+), 18 deletions(-) diff --git a/camera/src/realsense_camera_nodelet.cpp b/camera/src/realsense_camera_nodelet.cpp index 3a0e283855..b2df13dfbc 100644 --- a/camera/src/realsense_camera_nodelet.cpp +++ b/camera/src/realsense_camera_nodelet.cpp @@ -56,12 +56,13 @@ namespace realsense_camera // Stop device. if (is_device_started_ == true) { + ROS_INFO_STREAM(nodelet_name_ << " - Stopping camera"); rs_stop_device(rs_device_, 0); rs_delete_context(rs_context_, &rs_error_); checkError(); } - ROS_INFO_STREAM(nodelet_name_ << " - Stopping camera nodelet."); + ROS_INFO_STREAM(nodelet_name_ << " - Stopping..."); ros::shutdown(); } @@ -71,7 +72,7 @@ namespace realsense_camera void RealsenseNodelet::onInit() { nodelet_name_ = getName(); // Get the nodelet name - ROS_INFO_STREAM(nodelet_name_ << " - Starting camera nodelet."); + ROS_INFO_STREAM(nodelet_name_ << " - Starting..."); // Set default configurations. is_device_started_ = false; @@ -143,13 +144,13 @@ namespace realsense_camera // Enable streams. if (mode_.compare ("manual") == 0) { - ROS_INFO_STREAM(nodelet_name_ << " - Enabling Color Stream: manual mode"); + ROS_INFO_STREAM(nodelet_name_ << " - Enabling Color stream: manual mode"); rs_enable_stream(rs_device_, RS_STREAM_COLOR, color_width_, color_height_, COLOR_FORMAT, color_fps_, &rs_error_); checkError(); } else { - ROS_INFO_STREAM(nodelet_name_ << " - Enabling Color Stream: preset mode"); + ROS_INFO_STREAM(nodelet_name_ << " - Enabling Color stream: preset mode"); rs_enable_stream_preset(rs_device_, RS_STREAM_COLOR, RS_PRESET_BEST_QUALITY, &rs_error_); checkError(); } @@ -166,13 +167,13 @@ namespace realsense_camera // Enable streams. if (mode_.compare ("manual") == 0) { - ROS_INFO_STREAM(nodelet_name_ << " - Enabling Depth Stream: manual mode"); + ROS_INFO_STREAM(nodelet_name_ << " - Enabling Depth stream: manual mode"); rs_enable_stream(rs_device_, RS_STREAM_DEPTH, depth_width_, depth_height_, DEPTH_FORMAT, depth_fps_, &rs_error_); checkError(); } else { - ROS_INFO_STREAM(nodelet_name_ << " - Enabling Depth Stream: preset mode"); + ROS_INFO_STREAM(nodelet_name_ << " - Enabling Depth stream: preset mode"); rs_enable_stream_preset(rs_device_, RS_STREAM_DEPTH, RS_PRESET_BEST_QUALITY, &rs_error_); checkError(); } @@ -189,13 +190,13 @@ namespace realsense_camera // Enable streams. if (mode_.compare ("manual") == 0) { - ROS_INFO_STREAM(nodelet_name_ << " - Enabling Infrared Stream: manual mode"); + ROS_INFO_STREAM(nodelet_name_ << " - Enabling Infrared stream: manual mode"); rs_enable_stream(rs_device_, RS_STREAM_INFRARED, depth_width_, depth_height_, IR1_FORMAT, depth_fps_, &rs_error_); checkError(); } else { - ROS_INFO_STREAM(nodelet_name_ << " - Enabling Infrared Stream: preset mode"); + ROS_INFO_STREAM(nodelet_name_ << " - Enabling Infrared stream: preset mode"); rs_enable_stream_preset(rs_device_, RS_STREAM_INFRARED, RS_PRESET_BEST_QUALITY, &rs_error_); checkError(); } @@ -212,12 +213,12 @@ namespace realsense_camera // Enable streams. if (mode_.compare ("manual") == 0) { - ROS_INFO_STREAM(nodelet_name_ << " - Enabling Infrared2 Stream: manual mode"); + ROS_INFO_STREAM(nodelet_name_ << " - Enabling Infrared2 stream: manual mode"); rs_enable_stream(rs_device_, RS_STREAM_INFRARED2, depth_width_, depth_height_, IR2_FORMAT, depth_fps_, 0); } else { - ROS_INFO_STREAM(nodelet_name_ << " - Enabling Infrared2 Stream: preset mode"); + ROS_INFO_STREAM(nodelet_name_ << " - Enabling Infrared2 stream: preset mode"); rs_enable_stream_preset(rs_device_, RS_STREAM_INFRARED2, RS_PRESET_BEST_QUALITY, 0); } @@ -331,7 +332,7 @@ namespace realsense_camera { if (enable_depth_ == false && enable_color_ == false) { - ROS_ERROR_STREAM(nodelet_name_ << " - None of the streams are enabled. Exiting."); + ROS_ERROR_STREAM(nodelet_name_ << " - None of the streams are enabled. Exiting!"); return false; } @@ -403,6 +404,7 @@ namespace realsense_camera setStaticCameraOptions(); // Start device. + ROS_INFO_STREAM(nodelet_name_ << " - Starting camera"); rs_start_device(rs_device_, &rs_error_); checkError(); @@ -703,30 +705,30 @@ namespace realsense_camera { if (rs_is_device_streaming(rs_device_, 0) == 1) { + ROS_INFO_STREAM(nodelet_name_ << " - Stopping camera"); rs_stop_device(rs_device_, &rs_error_); checkError(); - ROS_INFO_STREAM(nodelet_name_ << " - Device Stopped"); } //disable depth, infrared1 and infrared2 streams + ROS_INFO_STREAM(nodelet_name_ << " - Disabling Depth stream"); rs_disable_stream(rs_device_, RS_STREAM_DEPTH, &rs_error_); checkError(); - ROS_INFO_STREAM(nodelet_name_ << " - Depth Stream Disabled"); + ROS_INFO_STREAM(nodelet_name_ << " - Disabling Infrared stream"); rs_disable_stream(rs_device_, RS_STREAM_INFRARED, &rs_error_); checkError(); - ROS_INFO_STREAM(nodelet_name_ << " - Infrared1 stream Disabled"); + ROS_INFO_STREAM(nodelet_name_ << " - Disabling Infrared2 stream"); rs_disable_stream(rs_device_, RS_STREAM_INFRARED2, &rs_error_); checkError(); - ROS_INFO_STREAM(nodelet_name_ << " - Infrared2 stream Disabled"); if (rs_is_device_streaming(rs_device_, 0) == 0) { + ROS_INFO_STREAM(nodelet_name_ << " - Starting camera"); rs_start_device(rs_device_, &rs_error_); checkError(); - ROS_INFO_STREAM(nodelet_name_ << " - Device Started"); } } @@ -734,9 +736,9 @@ namespace realsense_camera { if (rs_is_device_streaming(rs_device_, 0) == 1) { + ROS_INFO_STREAM(nodelet_name_ << " - Stopping camera"); rs_stop_device(rs_device_, &rs_error_); checkError(); - ROS_INFO_STREAM(nodelet_name_ << " - Device Stopped"); } enableDepthStream(); @@ -745,9 +747,9 @@ namespace realsense_camera if (rs_is_device_streaming(rs_device_, 0) == 0) { + ROS_INFO_STREAM(nodelet_name_ << " - Starting camera"); rs_start_device(rs_device_, &rs_error_); checkError(); - ROS_INFO_STREAM(nodelet_name_ << " - Device Started"); } } From 16ce4ec803c026243a7b88d6135128bb252f164f Mon Sep 17 00:00:00 2001 From: rjingar Date: Fri, 20 May 2016 09:17:25 -0700 Subject: [PATCH 100/124] Resolved testTransform unit test issue --- camera/test/realsense_camera_test_node.cpp | 9 ++++----- 1 file changed, 4 insertions(+), 5 deletions(-) diff --git a/camera/test/realsense_camera_test_node.cpp b/camera/test/realsense_camera_test_node.cpp index 1380b27665..f514370b88 100644 --- a/camera/test/realsense_camera_test_node.cpp +++ b/camera/test/realsense_camera_test_node.cpp @@ -543,12 +543,11 @@ TEST (RealsenseTests, testTransforms) { // make sure all transforms are being broadcast as expected tf::TransformListener tf_listener; - ros::Duration(1).sleep(); // must listen for ~1 sec or tf won't be found - EXPECT_TRUE(tf_listener.canTransform (BASE_DEF_FRAME, DEPTH_DEF_FRAME, ros::Time::now())); - EXPECT_TRUE(tf_listener.canTransform (DEPTH_DEF_FRAME, DEPTH_OPTICAL_DEF_FRAME, ros::Time::now())); - EXPECT_TRUE(tf_listener.canTransform (BASE_DEF_FRAME, COLOR_DEF_FRAME, ros::Time::now())); - EXPECT_TRUE(tf_listener.canTransform (COLOR_DEF_FRAME,COLOR_OPTICAL_DEF_FRAME, ros::Time::now())); + EXPECT_TRUE(tf_listener.waitForTransform (DEPTH_DEF_FRAME, BASE_DEF_FRAME, ros::Time(0), ros::Duration(3.0))); + EXPECT_TRUE(tf_listener.waitForTransform (DEPTH_OPTICAL_DEF_FRAME, DEPTH_DEF_FRAME, ros::Time(0), ros::Duration(3.0))); + EXPECT_TRUE(tf_listener.waitForTransform (COLOR_DEF_FRAME, BASE_DEF_FRAME, ros::Time(0), ros::Duration(3.0))); + EXPECT_TRUE(tf_listener.waitForTransform (COLOR_OPTICAL_DEF_FRAME, COLOR_DEF_FRAME, ros::Time(0), ros::Duration(3.0))); } TEST (RealsenseTests, testCameraOptions) From bacd46695ad55111f0b3a2c978576c6a5c99e6f5 Mon Sep 17 00:00:00 2001 From: Mark D Horn Date: Mon, 23 May 2016 18:10:55 -0700 Subject: [PATCH 101/124] Rename package directory Make the package directory name consistent with the package name. --- {camera => realsense_camera}/CHANGELOG.rst | 0 {camera => realsense_camera}/CMakeLists.txt | 0 {camera => realsense_camera}/README.md | 0 {camera => realsense_camera}/cfg/camera_params.cfg | 0 .../includes/realsense_r200_nodelet.launch.xml | 0 .../launch/realsense_r200_navigation.launch | 0 .../realsense_r200_nodelet_standalone_manual.launch | 0 .../realsense_r200_nodelet_standalone_preset.launch | 0 .../launch/realsense_r200_rgbd.launch | 0 {camera => realsense_camera}/licenses/License.txt | 0 .../navigation/turtlebot/README.md | 0 .../navigation/turtlebot/doc/img/bag_screen.png | Bin .../navigation/turtlebot/doc/img/mapping_screen.png | Bin .../navigation/turtlebot/doc/img/screen-ds4-nav.png | Bin .../navigation/turtlebot/doc/style-doc.css | 0 .../turtlebot/install_realsense_navigation.sh | 0 .../navigation/turtlebot/launch/amcl.launch | 0 .../navigation/turtlebot/launch/gmapping.launch | 0 .../turtlebot/launch/navigation_demo.launch | 0 .../launch/realsense_robot_description.launch | 0 .../turtlebot/launch/simulate_mapping.launch | 0 .../navigation/turtlebot/package.xml | 0 .../robot_description/custom_costmap_params.yaml | 0 .../kobuki_minimal_r200.urdf.xacro | 0 .../robot_description/meshes/sensors/r200.dae | 0 .../meshes/sensors/r200_entire.dae | 0 .../meshes/sensors/r200_entire/texture0.jpg | Bin .../robot_description/meshes/sensors/r200_only.dae | 0 .../turtlebot/robot_description/r200.launch.xml | 0 .../turtlebot_library_extended.urdf.xacro | 0 .../robot_description/urdf/sensors/r200.urdf.xacro | 0 .../urdf/stacks/minimal.urdf.xacro | 0 .../navigation/turtlebot/rviz/navigation_r200.rviz | 0 .../rviz/navigation_r200_without_depth.rviz | 0 {camera => realsense_camera}/package.xml | 0 .../realsense_camera_nodelet_plugins.xml | 0 .../rviz/realsenseRvizConfiguration1.rviz | 0 .../rviz/realsenseRvizConfiguration2.rviz | 0 .../rviz/realsenseRvizConfiguration3.rviz | 0 .../src/realsense_camera_nodelet.cpp | 0 .../src/realsense_camera_nodelet.h | 0 .../srv/cameraConfiguration.srv | 0 .../test/realsense_camera_test_node.cpp | 0 .../test/realsense_camera_test_node.h | 0 .../test/realsense_camera_test_rgbd_node.cpp | 0 .../test/realsense_camera_test_rgbd_node.h | 0 .../test/realsense_r200_color_only.test | 0 .../test/realsense_r200_depth_only.test | 0 ...lsense_r200_dynamic_camera_options_params.launch | 0 .../test/realsense_r200_resolution.test | 0 .../test/realsense_r200_rgbd.test | 0 ...alsense_r200_static_camera_options_params.launch | 0 .../realsense_r200_stream_options_params.launch | 0 53 files changed, 0 insertions(+), 0 deletions(-) rename {camera => realsense_camera}/CHANGELOG.rst (100%) rename {camera => realsense_camera}/CMakeLists.txt (100%) rename {camera => realsense_camera}/README.md (100%) rename {camera => realsense_camera}/cfg/camera_params.cfg (100%) rename {camera => realsense_camera}/launch/includes/realsense_r200_nodelet.launch.xml (100%) rename {camera => realsense_camera}/launch/realsense_r200_navigation.launch (100%) rename {camera => realsense_camera}/launch/realsense_r200_nodelet_standalone_manual.launch (100%) rename {camera => realsense_camera}/launch/realsense_r200_nodelet_standalone_preset.launch (100%) rename {camera => realsense_camera}/launch/realsense_r200_rgbd.launch (100%) rename {camera => realsense_camera}/licenses/License.txt (100%) rename {camera => realsense_camera}/navigation/turtlebot/README.md (100%) rename {camera => realsense_camera}/navigation/turtlebot/doc/img/bag_screen.png (100%) rename {camera => realsense_camera}/navigation/turtlebot/doc/img/mapping_screen.png (100%) rename {camera => realsense_camera}/navigation/turtlebot/doc/img/screen-ds4-nav.png (100%) rename {camera => realsense_camera}/navigation/turtlebot/doc/style-doc.css (100%) rename {camera => realsense_camera}/navigation/turtlebot/install_realsense_navigation.sh (100%) rename {camera => realsense_camera}/navigation/turtlebot/launch/amcl.launch (100%) rename {camera => realsense_camera}/navigation/turtlebot/launch/gmapping.launch (100%) rename {camera => realsense_camera}/navigation/turtlebot/launch/navigation_demo.launch (100%) rename {camera => realsense_camera}/navigation/turtlebot/launch/realsense_robot_description.launch (100%) rename {camera => realsense_camera}/navigation/turtlebot/launch/simulate_mapping.launch (100%) rename {camera => realsense_camera}/navigation/turtlebot/package.xml (100%) rename {camera => realsense_camera}/navigation/turtlebot/robot_description/custom_costmap_params.yaml (100%) rename {camera => realsense_camera}/navigation/turtlebot/robot_description/kobuki_minimal_r200.urdf.xacro (100%) rename {camera => realsense_camera}/navigation/turtlebot/robot_description/meshes/sensors/r200.dae (100%) rename {camera => realsense_camera}/navigation/turtlebot/robot_description/meshes/sensors/r200_entire.dae (100%) rename {camera => realsense_camera}/navigation/turtlebot/robot_description/meshes/sensors/r200_entire/texture0.jpg (100%) rename {camera => realsense_camera}/navigation/turtlebot/robot_description/meshes/sensors/r200_only.dae (100%) rename {camera => realsense_camera}/navigation/turtlebot/robot_description/r200.launch.xml (100%) rename {camera => realsense_camera}/navigation/turtlebot/robot_description/turtlebot_library_extended.urdf.xacro (100%) rename {camera => realsense_camera}/navigation/turtlebot/robot_description/urdf/sensors/r200.urdf.xacro (100%) rename {camera => realsense_camera}/navigation/turtlebot/robot_description/urdf/stacks/minimal.urdf.xacro (100%) rename {camera => realsense_camera}/navigation/turtlebot/rviz/navigation_r200.rviz (100%) rename {camera => realsense_camera}/navigation/turtlebot/rviz/navigation_r200_without_depth.rviz (100%) rename {camera => realsense_camera}/package.xml (100%) rename {camera => realsense_camera}/realsense_camera_nodelet_plugins.xml (100%) rename {camera => realsense_camera}/rviz/realsenseRvizConfiguration1.rviz (100%) rename {camera => realsense_camera}/rviz/realsenseRvizConfiguration2.rviz (100%) rename {camera => realsense_camera}/rviz/realsenseRvizConfiguration3.rviz (100%) rename {camera => realsense_camera}/src/realsense_camera_nodelet.cpp (100%) rename {camera => realsense_camera}/src/realsense_camera_nodelet.h (100%) rename {camera => realsense_camera}/srv/cameraConfiguration.srv (100%) rename {camera => realsense_camera}/test/realsense_camera_test_node.cpp (100%) rename {camera => realsense_camera}/test/realsense_camera_test_node.h (100%) rename {camera => realsense_camera}/test/realsense_camera_test_rgbd_node.cpp (100%) rename {camera => realsense_camera}/test/realsense_camera_test_rgbd_node.h (100%) rename {camera => realsense_camera}/test/realsense_r200_color_only.test (100%) rename {camera => realsense_camera}/test/realsense_r200_depth_only.test (100%) rename {camera => realsense_camera}/test/realsense_r200_dynamic_camera_options_params.launch (100%) rename {camera => realsense_camera}/test/realsense_r200_resolution.test (100%) rename {camera => realsense_camera}/test/realsense_r200_rgbd.test (100%) rename {camera => realsense_camera}/test/realsense_r200_static_camera_options_params.launch (100%) rename {camera => realsense_camera}/test/realsense_r200_stream_options_params.launch (100%) diff --git a/camera/CHANGELOG.rst b/realsense_camera/CHANGELOG.rst similarity index 100% rename from camera/CHANGELOG.rst rename to realsense_camera/CHANGELOG.rst diff --git a/camera/CMakeLists.txt b/realsense_camera/CMakeLists.txt similarity index 100% rename from camera/CMakeLists.txt rename to realsense_camera/CMakeLists.txt diff --git a/camera/README.md b/realsense_camera/README.md similarity index 100% rename from camera/README.md rename to realsense_camera/README.md diff --git a/camera/cfg/camera_params.cfg b/realsense_camera/cfg/camera_params.cfg similarity index 100% rename from camera/cfg/camera_params.cfg rename to realsense_camera/cfg/camera_params.cfg diff --git a/camera/launch/includes/realsense_r200_nodelet.launch.xml b/realsense_camera/launch/includes/realsense_r200_nodelet.launch.xml similarity index 100% rename from camera/launch/includes/realsense_r200_nodelet.launch.xml rename to realsense_camera/launch/includes/realsense_r200_nodelet.launch.xml diff --git a/camera/launch/realsense_r200_navigation.launch b/realsense_camera/launch/realsense_r200_navigation.launch similarity index 100% rename from camera/launch/realsense_r200_navigation.launch rename to realsense_camera/launch/realsense_r200_navigation.launch diff --git a/camera/launch/realsense_r200_nodelet_standalone_manual.launch b/realsense_camera/launch/realsense_r200_nodelet_standalone_manual.launch similarity index 100% rename from camera/launch/realsense_r200_nodelet_standalone_manual.launch rename to realsense_camera/launch/realsense_r200_nodelet_standalone_manual.launch diff --git a/camera/launch/realsense_r200_nodelet_standalone_preset.launch b/realsense_camera/launch/realsense_r200_nodelet_standalone_preset.launch similarity index 100% rename from camera/launch/realsense_r200_nodelet_standalone_preset.launch rename to realsense_camera/launch/realsense_r200_nodelet_standalone_preset.launch diff --git a/camera/launch/realsense_r200_rgbd.launch b/realsense_camera/launch/realsense_r200_rgbd.launch similarity index 100% rename from camera/launch/realsense_r200_rgbd.launch rename to realsense_camera/launch/realsense_r200_rgbd.launch diff --git a/camera/licenses/License.txt b/realsense_camera/licenses/License.txt similarity index 100% rename from camera/licenses/License.txt rename to realsense_camera/licenses/License.txt diff --git a/camera/navigation/turtlebot/README.md b/realsense_camera/navigation/turtlebot/README.md similarity index 100% rename from camera/navigation/turtlebot/README.md rename to realsense_camera/navigation/turtlebot/README.md diff --git a/camera/navigation/turtlebot/doc/img/bag_screen.png b/realsense_camera/navigation/turtlebot/doc/img/bag_screen.png similarity index 100% rename from camera/navigation/turtlebot/doc/img/bag_screen.png rename to realsense_camera/navigation/turtlebot/doc/img/bag_screen.png diff --git a/camera/navigation/turtlebot/doc/img/mapping_screen.png b/realsense_camera/navigation/turtlebot/doc/img/mapping_screen.png similarity index 100% rename from camera/navigation/turtlebot/doc/img/mapping_screen.png rename to realsense_camera/navigation/turtlebot/doc/img/mapping_screen.png diff --git a/camera/navigation/turtlebot/doc/img/screen-ds4-nav.png b/realsense_camera/navigation/turtlebot/doc/img/screen-ds4-nav.png similarity index 100% rename from camera/navigation/turtlebot/doc/img/screen-ds4-nav.png rename to realsense_camera/navigation/turtlebot/doc/img/screen-ds4-nav.png diff --git a/camera/navigation/turtlebot/doc/style-doc.css b/realsense_camera/navigation/turtlebot/doc/style-doc.css similarity index 100% rename from camera/navigation/turtlebot/doc/style-doc.css rename to realsense_camera/navigation/turtlebot/doc/style-doc.css diff --git a/camera/navigation/turtlebot/install_realsense_navigation.sh b/realsense_camera/navigation/turtlebot/install_realsense_navigation.sh similarity index 100% rename from camera/navigation/turtlebot/install_realsense_navigation.sh rename to realsense_camera/navigation/turtlebot/install_realsense_navigation.sh diff --git a/camera/navigation/turtlebot/launch/amcl.launch b/realsense_camera/navigation/turtlebot/launch/amcl.launch similarity index 100% rename from camera/navigation/turtlebot/launch/amcl.launch rename to realsense_camera/navigation/turtlebot/launch/amcl.launch diff --git a/camera/navigation/turtlebot/launch/gmapping.launch b/realsense_camera/navigation/turtlebot/launch/gmapping.launch similarity index 100% rename from camera/navigation/turtlebot/launch/gmapping.launch rename to realsense_camera/navigation/turtlebot/launch/gmapping.launch diff --git a/camera/navigation/turtlebot/launch/navigation_demo.launch b/realsense_camera/navigation/turtlebot/launch/navigation_demo.launch similarity index 100% rename from camera/navigation/turtlebot/launch/navigation_demo.launch rename to realsense_camera/navigation/turtlebot/launch/navigation_demo.launch diff --git a/camera/navigation/turtlebot/launch/realsense_robot_description.launch b/realsense_camera/navigation/turtlebot/launch/realsense_robot_description.launch similarity index 100% rename from camera/navigation/turtlebot/launch/realsense_robot_description.launch rename to realsense_camera/navigation/turtlebot/launch/realsense_robot_description.launch diff --git a/camera/navigation/turtlebot/launch/simulate_mapping.launch b/realsense_camera/navigation/turtlebot/launch/simulate_mapping.launch similarity index 100% rename from camera/navigation/turtlebot/launch/simulate_mapping.launch rename to realsense_camera/navigation/turtlebot/launch/simulate_mapping.launch diff --git a/camera/navigation/turtlebot/package.xml b/realsense_camera/navigation/turtlebot/package.xml similarity index 100% rename from camera/navigation/turtlebot/package.xml rename to realsense_camera/navigation/turtlebot/package.xml diff --git a/camera/navigation/turtlebot/robot_description/custom_costmap_params.yaml b/realsense_camera/navigation/turtlebot/robot_description/custom_costmap_params.yaml similarity index 100% rename from camera/navigation/turtlebot/robot_description/custom_costmap_params.yaml rename to realsense_camera/navigation/turtlebot/robot_description/custom_costmap_params.yaml diff --git a/camera/navigation/turtlebot/robot_description/kobuki_minimal_r200.urdf.xacro b/realsense_camera/navigation/turtlebot/robot_description/kobuki_minimal_r200.urdf.xacro similarity index 100% rename from camera/navigation/turtlebot/robot_description/kobuki_minimal_r200.urdf.xacro rename to realsense_camera/navigation/turtlebot/robot_description/kobuki_minimal_r200.urdf.xacro diff --git a/camera/navigation/turtlebot/robot_description/meshes/sensors/r200.dae b/realsense_camera/navigation/turtlebot/robot_description/meshes/sensors/r200.dae similarity index 100% rename from camera/navigation/turtlebot/robot_description/meshes/sensors/r200.dae rename to realsense_camera/navigation/turtlebot/robot_description/meshes/sensors/r200.dae diff --git a/camera/navigation/turtlebot/robot_description/meshes/sensors/r200_entire.dae b/realsense_camera/navigation/turtlebot/robot_description/meshes/sensors/r200_entire.dae similarity index 100% rename from camera/navigation/turtlebot/robot_description/meshes/sensors/r200_entire.dae rename to realsense_camera/navigation/turtlebot/robot_description/meshes/sensors/r200_entire.dae diff --git a/camera/navigation/turtlebot/robot_description/meshes/sensors/r200_entire/texture0.jpg b/realsense_camera/navigation/turtlebot/robot_description/meshes/sensors/r200_entire/texture0.jpg similarity index 100% rename from camera/navigation/turtlebot/robot_description/meshes/sensors/r200_entire/texture0.jpg rename to realsense_camera/navigation/turtlebot/robot_description/meshes/sensors/r200_entire/texture0.jpg diff --git a/camera/navigation/turtlebot/robot_description/meshes/sensors/r200_only.dae b/realsense_camera/navigation/turtlebot/robot_description/meshes/sensors/r200_only.dae similarity index 100% rename from camera/navigation/turtlebot/robot_description/meshes/sensors/r200_only.dae rename to realsense_camera/navigation/turtlebot/robot_description/meshes/sensors/r200_only.dae diff --git a/camera/navigation/turtlebot/robot_description/r200.launch.xml b/realsense_camera/navigation/turtlebot/robot_description/r200.launch.xml similarity index 100% rename from camera/navigation/turtlebot/robot_description/r200.launch.xml rename to realsense_camera/navigation/turtlebot/robot_description/r200.launch.xml diff --git a/camera/navigation/turtlebot/robot_description/turtlebot_library_extended.urdf.xacro b/realsense_camera/navigation/turtlebot/robot_description/turtlebot_library_extended.urdf.xacro similarity index 100% rename from camera/navigation/turtlebot/robot_description/turtlebot_library_extended.urdf.xacro rename to realsense_camera/navigation/turtlebot/robot_description/turtlebot_library_extended.urdf.xacro diff --git a/camera/navigation/turtlebot/robot_description/urdf/sensors/r200.urdf.xacro b/realsense_camera/navigation/turtlebot/robot_description/urdf/sensors/r200.urdf.xacro similarity index 100% rename from camera/navigation/turtlebot/robot_description/urdf/sensors/r200.urdf.xacro rename to realsense_camera/navigation/turtlebot/robot_description/urdf/sensors/r200.urdf.xacro diff --git a/camera/navigation/turtlebot/robot_description/urdf/stacks/minimal.urdf.xacro b/realsense_camera/navigation/turtlebot/robot_description/urdf/stacks/minimal.urdf.xacro similarity index 100% rename from camera/navigation/turtlebot/robot_description/urdf/stacks/minimal.urdf.xacro rename to realsense_camera/navigation/turtlebot/robot_description/urdf/stacks/minimal.urdf.xacro diff --git a/camera/navigation/turtlebot/rviz/navigation_r200.rviz b/realsense_camera/navigation/turtlebot/rviz/navigation_r200.rviz similarity index 100% rename from camera/navigation/turtlebot/rviz/navigation_r200.rviz rename to realsense_camera/navigation/turtlebot/rviz/navigation_r200.rviz diff --git a/camera/navigation/turtlebot/rviz/navigation_r200_without_depth.rviz b/realsense_camera/navigation/turtlebot/rviz/navigation_r200_without_depth.rviz similarity index 100% rename from camera/navigation/turtlebot/rviz/navigation_r200_without_depth.rviz rename to realsense_camera/navigation/turtlebot/rviz/navigation_r200_without_depth.rviz diff --git a/camera/package.xml b/realsense_camera/package.xml similarity index 100% rename from camera/package.xml rename to realsense_camera/package.xml diff --git a/camera/realsense_camera_nodelet_plugins.xml b/realsense_camera/realsense_camera_nodelet_plugins.xml similarity index 100% rename from camera/realsense_camera_nodelet_plugins.xml rename to realsense_camera/realsense_camera_nodelet_plugins.xml diff --git a/camera/rviz/realsenseRvizConfiguration1.rviz b/realsense_camera/rviz/realsenseRvizConfiguration1.rviz similarity index 100% rename from camera/rviz/realsenseRvizConfiguration1.rviz rename to realsense_camera/rviz/realsenseRvizConfiguration1.rviz diff --git a/camera/rviz/realsenseRvizConfiguration2.rviz b/realsense_camera/rviz/realsenseRvizConfiguration2.rviz similarity index 100% rename from camera/rviz/realsenseRvizConfiguration2.rviz rename to realsense_camera/rviz/realsenseRvizConfiguration2.rviz diff --git a/camera/rviz/realsenseRvizConfiguration3.rviz b/realsense_camera/rviz/realsenseRvizConfiguration3.rviz similarity index 100% rename from camera/rviz/realsenseRvizConfiguration3.rviz rename to realsense_camera/rviz/realsenseRvizConfiguration3.rviz diff --git a/camera/src/realsense_camera_nodelet.cpp b/realsense_camera/src/realsense_camera_nodelet.cpp similarity index 100% rename from camera/src/realsense_camera_nodelet.cpp rename to realsense_camera/src/realsense_camera_nodelet.cpp diff --git a/camera/src/realsense_camera_nodelet.h b/realsense_camera/src/realsense_camera_nodelet.h similarity index 100% rename from camera/src/realsense_camera_nodelet.h rename to realsense_camera/src/realsense_camera_nodelet.h diff --git a/camera/srv/cameraConfiguration.srv b/realsense_camera/srv/cameraConfiguration.srv similarity index 100% rename from camera/srv/cameraConfiguration.srv rename to realsense_camera/srv/cameraConfiguration.srv diff --git a/camera/test/realsense_camera_test_node.cpp b/realsense_camera/test/realsense_camera_test_node.cpp similarity index 100% rename from camera/test/realsense_camera_test_node.cpp rename to realsense_camera/test/realsense_camera_test_node.cpp diff --git a/camera/test/realsense_camera_test_node.h b/realsense_camera/test/realsense_camera_test_node.h similarity index 100% rename from camera/test/realsense_camera_test_node.h rename to realsense_camera/test/realsense_camera_test_node.h diff --git a/camera/test/realsense_camera_test_rgbd_node.cpp b/realsense_camera/test/realsense_camera_test_rgbd_node.cpp similarity index 100% rename from camera/test/realsense_camera_test_rgbd_node.cpp rename to realsense_camera/test/realsense_camera_test_rgbd_node.cpp diff --git a/camera/test/realsense_camera_test_rgbd_node.h b/realsense_camera/test/realsense_camera_test_rgbd_node.h similarity index 100% rename from camera/test/realsense_camera_test_rgbd_node.h rename to realsense_camera/test/realsense_camera_test_rgbd_node.h diff --git a/camera/test/realsense_r200_color_only.test b/realsense_camera/test/realsense_r200_color_only.test similarity index 100% rename from camera/test/realsense_r200_color_only.test rename to realsense_camera/test/realsense_r200_color_only.test diff --git a/camera/test/realsense_r200_depth_only.test b/realsense_camera/test/realsense_r200_depth_only.test similarity index 100% rename from camera/test/realsense_r200_depth_only.test rename to realsense_camera/test/realsense_r200_depth_only.test diff --git a/camera/test/realsense_r200_dynamic_camera_options_params.launch b/realsense_camera/test/realsense_r200_dynamic_camera_options_params.launch similarity index 100% rename from camera/test/realsense_r200_dynamic_camera_options_params.launch rename to realsense_camera/test/realsense_r200_dynamic_camera_options_params.launch diff --git a/camera/test/realsense_r200_resolution.test b/realsense_camera/test/realsense_r200_resolution.test similarity index 100% rename from camera/test/realsense_r200_resolution.test rename to realsense_camera/test/realsense_r200_resolution.test diff --git a/camera/test/realsense_r200_rgbd.test b/realsense_camera/test/realsense_r200_rgbd.test similarity index 100% rename from camera/test/realsense_r200_rgbd.test rename to realsense_camera/test/realsense_r200_rgbd.test diff --git a/camera/test/realsense_r200_static_camera_options_params.launch b/realsense_camera/test/realsense_r200_static_camera_options_params.launch similarity index 100% rename from camera/test/realsense_r200_static_camera_options_params.launch rename to realsense_camera/test/realsense_r200_static_camera_options_params.launch diff --git a/camera/test/realsense_r200_stream_options_params.launch b/realsense_camera/test/realsense_r200_stream_options_params.launch similarity index 100% rename from camera/test/realsense_r200_stream_options_params.launch rename to realsense_camera/test/realsense_r200_stream_options_params.launch From 338dbcffe579ac241fa0821868a9bbeb9aa9f584 Mon Sep 17 00:00:00 2001 From: Matt Hansen Date: Wed, 25 May 2016 10:31:44 -0700 Subject: [PATCH 102/124] Update README to include rosdep install Updated build directions to include 'rosdep install' step. --- camera/README.md | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/camera/README.md b/camera/README.md index 6bf71a854f..b541db06cc 100644 --- a/camera/README.md +++ b/camera/README.md @@ -19,8 +19,9 @@ If this does not work, you should first fix this issue before continuing with th #####Building package: -* Setup ROS and create a local catkin workspace. -* Compile the realsense_camera package by executing the catkin_make command. +* Install ROS and create a local catkin workspace (see [wiki.ros.org](http://wiki.ros.org/) for instructions) +* Run `rosdep install realsense_camera` to install package dependencies +* Compile the realsense_camera package by executing the `catkin_make` command. Successful execution of command will build target “realsense_camera_nodelet” From 1303ce6a5a02b509fc4860214c71cc9a904a8c90 Mon Sep 17 00:00:00 2001 From: Mark D Horn Date: Mon, 23 May 2016 18:10:55 -0700 Subject: [PATCH 103/124] Rename package directory Make the package directory name consistent with the package name. --- {camera => realsense_camera}/CHANGELOG.rst | 0 {camera => realsense_camera}/CMakeLists.txt | 0 {camera => realsense_camera}/README.md | 0 {camera => realsense_camera}/cfg/camera_params.cfg | 0 .../includes/realsense_r200_nodelet.launch.xml | 0 .../launch/realsense_r200_navigation.launch | 0 .../realsense_r200_nodelet_standalone_manual.launch | 0 .../realsense_r200_nodelet_standalone_preset.launch | 0 .../launch/realsense_r200_rgbd.launch | 0 {camera => realsense_camera}/licenses/License.txt | 0 .../navigation/turtlebot/README.md | 0 .../navigation/turtlebot/doc/img/bag_screen.png | Bin .../navigation/turtlebot/doc/img/mapping_screen.png | Bin .../navigation/turtlebot/doc/img/screen-ds4-nav.png | Bin .../navigation/turtlebot/doc/style-doc.css | 0 .../turtlebot/install_realsense_navigation.sh | 0 .../navigation/turtlebot/launch/amcl.launch | 0 .../navigation/turtlebot/launch/gmapping.launch | 0 .../turtlebot/launch/navigation_demo.launch | 0 .../launch/realsense_robot_description.launch | 0 .../turtlebot/launch/simulate_mapping.launch | 0 .../navigation/turtlebot/package.xml | 0 .../robot_description/custom_costmap_params.yaml | 0 .../kobuki_minimal_r200.urdf.xacro | 0 .../robot_description/meshes/sensors/r200.dae | 0 .../meshes/sensors/r200_entire.dae | 0 .../meshes/sensors/r200_entire/texture0.jpg | Bin .../robot_description/meshes/sensors/r200_only.dae | 0 .../turtlebot/robot_description/r200.launch.xml | 0 .../turtlebot_library_extended.urdf.xacro | 0 .../robot_description/urdf/sensors/r200.urdf.xacro | 0 .../urdf/stacks/minimal.urdf.xacro | 0 .../navigation/turtlebot/rviz/navigation_r200.rviz | 0 .../rviz/navigation_r200_without_depth.rviz | 0 {camera => realsense_camera}/package.xml | 0 .../realsense_camera_nodelet_plugins.xml | 0 .../rviz/realsenseRvizConfiguration1.rviz | 0 .../rviz/realsenseRvizConfiguration2.rviz | 0 .../rviz/realsenseRvizConfiguration3.rviz | 0 .../src/realsense_camera_nodelet.cpp | 0 .../src/realsense_camera_nodelet.h | 0 .../srv/cameraConfiguration.srv | 0 .../test/realsense_camera_test_node.cpp | 0 .../test/realsense_camera_test_node.h | 0 .../test/realsense_camera_test_rgbd_node.cpp | 0 .../test/realsense_camera_test_rgbd_node.h | 0 .../test/realsense_r200_color_only.test | 0 .../test/realsense_r200_depth_only.test | 0 ...lsense_r200_dynamic_camera_options_params.launch | 0 .../test/realsense_r200_resolution.test | 0 .../test/realsense_r200_rgbd.test | 0 ...alsense_r200_static_camera_options_params.launch | 0 .../realsense_r200_stream_options_params.launch | 0 53 files changed, 0 insertions(+), 0 deletions(-) rename {camera => realsense_camera}/CHANGELOG.rst (100%) rename {camera => realsense_camera}/CMakeLists.txt (100%) rename {camera => realsense_camera}/README.md (100%) rename {camera => realsense_camera}/cfg/camera_params.cfg (100%) rename {camera => realsense_camera}/launch/includes/realsense_r200_nodelet.launch.xml (100%) rename {camera => realsense_camera}/launch/realsense_r200_navigation.launch (100%) rename {camera => realsense_camera}/launch/realsense_r200_nodelet_standalone_manual.launch (100%) rename {camera => realsense_camera}/launch/realsense_r200_nodelet_standalone_preset.launch (100%) rename {camera => realsense_camera}/launch/realsense_r200_rgbd.launch (100%) rename {camera => realsense_camera}/licenses/License.txt (100%) rename {camera => realsense_camera}/navigation/turtlebot/README.md (100%) rename {camera => realsense_camera}/navigation/turtlebot/doc/img/bag_screen.png (100%) rename {camera => realsense_camera}/navigation/turtlebot/doc/img/mapping_screen.png (100%) rename {camera => realsense_camera}/navigation/turtlebot/doc/img/screen-ds4-nav.png (100%) rename {camera => realsense_camera}/navigation/turtlebot/doc/style-doc.css (100%) rename {camera => realsense_camera}/navigation/turtlebot/install_realsense_navigation.sh (100%) rename {camera => realsense_camera}/navigation/turtlebot/launch/amcl.launch (100%) rename {camera => realsense_camera}/navigation/turtlebot/launch/gmapping.launch (100%) rename {camera => realsense_camera}/navigation/turtlebot/launch/navigation_demo.launch (100%) rename {camera => realsense_camera}/navigation/turtlebot/launch/realsense_robot_description.launch (100%) rename {camera => realsense_camera}/navigation/turtlebot/launch/simulate_mapping.launch (100%) rename {camera => realsense_camera}/navigation/turtlebot/package.xml (100%) rename {camera => realsense_camera}/navigation/turtlebot/robot_description/custom_costmap_params.yaml (100%) rename {camera => realsense_camera}/navigation/turtlebot/robot_description/kobuki_minimal_r200.urdf.xacro (100%) rename {camera => realsense_camera}/navigation/turtlebot/robot_description/meshes/sensors/r200.dae (100%) rename {camera => realsense_camera}/navigation/turtlebot/robot_description/meshes/sensors/r200_entire.dae (100%) rename {camera => realsense_camera}/navigation/turtlebot/robot_description/meshes/sensors/r200_entire/texture0.jpg (100%) rename {camera => realsense_camera}/navigation/turtlebot/robot_description/meshes/sensors/r200_only.dae (100%) rename {camera => realsense_camera}/navigation/turtlebot/robot_description/r200.launch.xml (100%) rename {camera => realsense_camera}/navigation/turtlebot/robot_description/turtlebot_library_extended.urdf.xacro (100%) rename {camera => realsense_camera}/navigation/turtlebot/robot_description/urdf/sensors/r200.urdf.xacro (100%) rename {camera => realsense_camera}/navigation/turtlebot/robot_description/urdf/stacks/minimal.urdf.xacro (100%) rename {camera => realsense_camera}/navigation/turtlebot/rviz/navigation_r200.rviz (100%) rename {camera => realsense_camera}/navigation/turtlebot/rviz/navigation_r200_without_depth.rviz (100%) rename {camera => realsense_camera}/package.xml (100%) rename {camera => realsense_camera}/realsense_camera_nodelet_plugins.xml (100%) rename {camera => realsense_camera}/rviz/realsenseRvizConfiguration1.rviz (100%) rename {camera => realsense_camera}/rviz/realsenseRvizConfiguration2.rviz (100%) rename {camera => realsense_camera}/rviz/realsenseRvizConfiguration3.rviz (100%) rename {camera => realsense_camera}/src/realsense_camera_nodelet.cpp (100%) rename {camera => realsense_camera}/src/realsense_camera_nodelet.h (100%) rename {camera => realsense_camera}/srv/cameraConfiguration.srv (100%) rename {camera => realsense_camera}/test/realsense_camera_test_node.cpp (100%) rename {camera => realsense_camera}/test/realsense_camera_test_node.h (100%) rename {camera => realsense_camera}/test/realsense_camera_test_rgbd_node.cpp (100%) rename {camera => realsense_camera}/test/realsense_camera_test_rgbd_node.h (100%) rename {camera => realsense_camera}/test/realsense_r200_color_only.test (100%) rename {camera => realsense_camera}/test/realsense_r200_depth_only.test (100%) rename {camera => realsense_camera}/test/realsense_r200_dynamic_camera_options_params.launch (100%) rename {camera => realsense_camera}/test/realsense_r200_resolution.test (100%) rename {camera => realsense_camera}/test/realsense_r200_rgbd.test (100%) rename {camera => realsense_camera}/test/realsense_r200_static_camera_options_params.launch (100%) rename {camera => realsense_camera}/test/realsense_r200_stream_options_params.launch (100%) diff --git a/camera/CHANGELOG.rst b/realsense_camera/CHANGELOG.rst similarity index 100% rename from camera/CHANGELOG.rst rename to realsense_camera/CHANGELOG.rst diff --git a/camera/CMakeLists.txt b/realsense_camera/CMakeLists.txt similarity index 100% rename from camera/CMakeLists.txt rename to realsense_camera/CMakeLists.txt diff --git a/camera/README.md b/realsense_camera/README.md similarity index 100% rename from camera/README.md rename to realsense_camera/README.md diff --git a/camera/cfg/camera_params.cfg b/realsense_camera/cfg/camera_params.cfg similarity index 100% rename from camera/cfg/camera_params.cfg rename to realsense_camera/cfg/camera_params.cfg diff --git a/camera/launch/includes/realsense_r200_nodelet.launch.xml b/realsense_camera/launch/includes/realsense_r200_nodelet.launch.xml similarity index 100% rename from camera/launch/includes/realsense_r200_nodelet.launch.xml rename to realsense_camera/launch/includes/realsense_r200_nodelet.launch.xml diff --git a/camera/launch/realsense_r200_navigation.launch b/realsense_camera/launch/realsense_r200_navigation.launch similarity index 100% rename from camera/launch/realsense_r200_navigation.launch rename to realsense_camera/launch/realsense_r200_navigation.launch diff --git a/camera/launch/realsense_r200_nodelet_standalone_manual.launch b/realsense_camera/launch/realsense_r200_nodelet_standalone_manual.launch similarity index 100% rename from camera/launch/realsense_r200_nodelet_standalone_manual.launch rename to realsense_camera/launch/realsense_r200_nodelet_standalone_manual.launch diff --git a/camera/launch/realsense_r200_nodelet_standalone_preset.launch b/realsense_camera/launch/realsense_r200_nodelet_standalone_preset.launch similarity index 100% rename from camera/launch/realsense_r200_nodelet_standalone_preset.launch rename to realsense_camera/launch/realsense_r200_nodelet_standalone_preset.launch diff --git a/camera/launch/realsense_r200_rgbd.launch b/realsense_camera/launch/realsense_r200_rgbd.launch similarity index 100% rename from camera/launch/realsense_r200_rgbd.launch rename to realsense_camera/launch/realsense_r200_rgbd.launch diff --git a/camera/licenses/License.txt b/realsense_camera/licenses/License.txt similarity index 100% rename from camera/licenses/License.txt rename to realsense_camera/licenses/License.txt diff --git a/camera/navigation/turtlebot/README.md b/realsense_camera/navigation/turtlebot/README.md similarity index 100% rename from camera/navigation/turtlebot/README.md rename to realsense_camera/navigation/turtlebot/README.md diff --git a/camera/navigation/turtlebot/doc/img/bag_screen.png b/realsense_camera/navigation/turtlebot/doc/img/bag_screen.png similarity index 100% rename from camera/navigation/turtlebot/doc/img/bag_screen.png rename to realsense_camera/navigation/turtlebot/doc/img/bag_screen.png diff --git a/camera/navigation/turtlebot/doc/img/mapping_screen.png b/realsense_camera/navigation/turtlebot/doc/img/mapping_screen.png similarity index 100% rename from camera/navigation/turtlebot/doc/img/mapping_screen.png rename to realsense_camera/navigation/turtlebot/doc/img/mapping_screen.png diff --git a/camera/navigation/turtlebot/doc/img/screen-ds4-nav.png b/realsense_camera/navigation/turtlebot/doc/img/screen-ds4-nav.png similarity index 100% rename from camera/navigation/turtlebot/doc/img/screen-ds4-nav.png rename to realsense_camera/navigation/turtlebot/doc/img/screen-ds4-nav.png diff --git a/camera/navigation/turtlebot/doc/style-doc.css b/realsense_camera/navigation/turtlebot/doc/style-doc.css similarity index 100% rename from camera/navigation/turtlebot/doc/style-doc.css rename to realsense_camera/navigation/turtlebot/doc/style-doc.css diff --git a/camera/navigation/turtlebot/install_realsense_navigation.sh b/realsense_camera/navigation/turtlebot/install_realsense_navigation.sh similarity index 100% rename from camera/navigation/turtlebot/install_realsense_navigation.sh rename to realsense_camera/navigation/turtlebot/install_realsense_navigation.sh diff --git a/camera/navigation/turtlebot/launch/amcl.launch b/realsense_camera/navigation/turtlebot/launch/amcl.launch similarity index 100% rename from camera/navigation/turtlebot/launch/amcl.launch rename to realsense_camera/navigation/turtlebot/launch/amcl.launch diff --git a/camera/navigation/turtlebot/launch/gmapping.launch b/realsense_camera/navigation/turtlebot/launch/gmapping.launch similarity index 100% rename from camera/navigation/turtlebot/launch/gmapping.launch rename to realsense_camera/navigation/turtlebot/launch/gmapping.launch diff --git a/camera/navigation/turtlebot/launch/navigation_demo.launch b/realsense_camera/navigation/turtlebot/launch/navigation_demo.launch similarity index 100% rename from camera/navigation/turtlebot/launch/navigation_demo.launch rename to realsense_camera/navigation/turtlebot/launch/navigation_demo.launch diff --git a/camera/navigation/turtlebot/launch/realsense_robot_description.launch b/realsense_camera/navigation/turtlebot/launch/realsense_robot_description.launch similarity index 100% rename from camera/navigation/turtlebot/launch/realsense_robot_description.launch rename to realsense_camera/navigation/turtlebot/launch/realsense_robot_description.launch diff --git a/camera/navigation/turtlebot/launch/simulate_mapping.launch b/realsense_camera/navigation/turtlebot/launch/simulate_mapping.launch similarity index 100% rename from camera/navigation/turtlebot/launch/simulate_mapping.launch rename to realsense_camera/navigation/turtlebot/launch/simulate_mapping.launch diff --git a/camera/navigation/turtlebot/package.xml b/realsense_camera/navigation/turtlebot/package.xml similarity index 100% rename from camera/navigation/turtlebot/package.xml rename to realsense_camera/navigation/turtlebot/package.xml diff --git a/camera/navigation/turtlebot/robot_description/custom_costmap_params.yaml b/realsense_camera/navigation/turtlebot/robot_description/custom_costmap_params.yaml similarity index 100% rename from camera/navigation/turtlebot/robot_description/custom_costmap_params.yaml rename to realsense_camera/navigation/turtlebot/robot_description/custom_costmap_params.yaml diff --git a/camera/navigation/turtlebot/robot_description/kobuki_minimal_r200.urdf.xacro b/realsense_camera/navigation/turtlebot/robot_description/kobuki_minimal_r200.urdf.xacro similarity index 100% rename from camera/navigation/turtlebot/robot_description/kobuki_minimal_r200.urdf.xacro rename to realsense_camera/navigation/turtlebot/robot_description/kobuki_minimal_r200.urdf.xacro diff --git a/camera/navigation/turtlebot/robot_description/meshes/sensors/r200.dae b/realsense_camera/navigation/turtlebot/robot_description/meshes/sensors/r200.dae similarity index 100% rename from camera/navigation/turtlebot/robot_description/meshes/sensors/r200.dae rename to realsense_camera/navigation/turtlebot/robot_description/meshes/sensors/r200.dae diff --git a/camera/navigation/turtlebot/robot_description/meshes/sensors/r200_entire.dae b/realsense_camera/navigation/turtlebot/robot_description/meshes/sensors/r200_entire.dae similarity index 100% rename from camera/navigation/turtlebot/robot_description/meshes/sensors/r200_entire.dae rename to realsense_camera/navigation/turtlebot/robot_description/meshes/sensors/r200_entire.dae diff --git a/camera/navigation/turtlebot/robot_description/meshes/sensors/r200_entire/texture0.jpg b/realsense_camera/navigation/turtlebot/robot_description/meshes/sensors/r200_entire/texture0.jpg similarity index 100% rename from camera/navigation/turtlebot/robot_description/meshes/sensors/r200_entire/texture0.jpg rename to realsense_camera/navigation/turtlebot/robot_description/meshes/sensors/r200_entire/texture0.jpg diff --git a/camera/navigation/turtlebot/robot_description/meshes/sensors/r200_only.dae b/realsense_camera/navigation/turtlebot/robot_description/meshes/sensors/r200_only.dae similarity index 100% rename from camera/navigation/turtlebot/robot_description/meshes/sensors/r200_only.dae rename to realsense_camera/navigation/turtlebot/robot_description/meshes/sensors/r200_only.dae diff --git a/camera/navigation/turtlebot/robot_description/r200.launch.xml b/realsense_camera/navigation/turtlebot/robot_description/r200.launch.xml similarity index 100% rename from camera/navigation/turtlebot/robot_description/r200.launch.xml rename to realsense_camera/navigation/turtlebot/robot_description/r200.launch.xml diff --git a/camera/navigation/turtlebot/robot_description/turtlebot_library_extended.urdf.xacro b/realsense_camera/navigation/turtlebot/robot_description/turtlebot_library_extended.urdf.xacro similarity index 100% rename from camera/navigation/turtlebot/robot_description/turtlebot_library_extended.urdf.xacro rename to realsense_camera/navigation/turtlebot/robot_description/turtlebot_library_extended.urdf.xacro diff --git a/camera/navigation/turtlebot/robot_description/urdf/sensors/r200.urdf.xacro b/realsense_camera/navigation/turtlebot/robot_description/urdf/sensors/r200.urdf.xacro similarity index 100% rename from camera/navigation/turtlebot/robot_description/urdf/sensors/r200.urdf.xacro rename to realsense_camera/navigation/turtlebot/robot_description/urdf/sensors/r200.urdf.xacro diff --git a/camera/navigation/turtlebot/robot_description/urdf/stacks/minimal.urdf.xacro b/realsense_camera/navigation/turtlebot/robot_description/urdf/stacks/minimal.urdf.xacro similarity index 100% rename from camera/navigation/turtlebot/robot_description/urdf/stacks/minimal.urdf.xacro rename to realsense_camera/navigation/turtlebot/robot_description/urdf/stacks/minimal.urdf.xacro diff --git a/camera/navigation/turtlebot/rviz/navigation_r200.rviz b/realsense_camera/navigation/turtlebot/rviz/navigation_r200.rviz similarity index 100% rename from camera/navigation/turtlebot/rviz/navigation_r200.rviz rename to realsense_camera/navigation/turtlebot/rviz/navigation_r200.rviz diff --git a/camera/navigation/turtlebot/rviz/navigation_r200_without_depth.rviz b/realsense_camera/navigation/turtlebot/rviz/navigation_r200_without_depth.rviz similarity index 100% rename from camera/navigation/turtlebot/rviz/navigation_r200_without_depth.rviz rename to realsense_camera/navigation/turtlebot/rviz/navigation_r200_without_depth.rviz diff --git a/camera/package.xml b/realsense_camera/package.xml similarity index 100% rename from camera/package.xml rename to realsense_camera/package.xml diff --git a/camera/realsense_camera_nodelet_plugins.xml b/realsense_camera/realsense_camera_nodelet_plugins.xml similarity index 100% rename from camera/realsense_camera_nodelet_plugins.xml rename to realsense_camera/realsense_camera_nodelet_plugins.xml diff --git a/camera/rviz/realsenseRvizConfiguration1.rviz b/realsense_camera/rviz/realsenseRvizConfiguration1.rviz similarity index 100% rename from camera/rviz/realsenseRvizConfiguration1.rviz rename to realsense_camera/rviz/realsenseRvizConfiguration1.rviz diff --git a/camera/rviz/realsenseRvizConfiguration2.rviz b/realsense_camera/rviz/realsenseRvizConfiguration2.rviz similarity index 100% rename from camera/rviz/realsenseRvizConfiguration2.rviz rename to realsense_camera/rviz/realsenseRvizConfiguration2.rviz diff --git a/camera/rviz/realsenseRvizConfiguration3.rviz b/realsense_camera/rviz/realsenseRvizConfiguration3.rviz similarity index 100% rename from camera/rviz/realsenseRvizConfiguration3.rviz rename to realsense_camera/rviz/realsenseRvizConfiguration3.rviz diff --git a/camera/src/realsense_camera_nodelet.cpp b/realsense_camera/src/realsense_camera_nodelet.cpp similarity index 100% rename from camera/src/realsense_camera_nodelet.cpp rename to realsense_camera/src/realsense_camera_nodelet.cpp diff --git a/camera/src/realsense_camera_nodelet.h b/realsense_camera/src/realsense_camera_nodelet.h similarity index 100% rename from camera/src/realsense_camera_nodelet.h rename to realsense_camera/src/realsense_camera_nodelet.h diff --git a/camera/srv/cameraConfiguration.srv b/realsense_camera/srv/cameraConfiguration.srv similarity index 100% rename from camera/srv/cameraConfiguration.srv rename to realsense_camera/srv/cameraConfiguration.srv diff --git a/camera/test/realsense_camera_test_node.cpp b/realsense_camera/test/realsense_camera_test_node.cpp similarity index 100% rename from camera/test/realsense_camera_test_node.cpp rename to realsense_camera/test/realsense_camera_test_node.cpp diff --git a/camera/test/realsense_camera_test_node.h b/realsense_camera/test/realsense_camera_test_node.h similarity index 100% rename from camera/test/realsense_camera_test_node.h rename to realsense_camera/test/realsense_camera_test_node.h diff --git a/camera/test/realsense_camera_test_rgbd_node.cpp b/realsense_camera/test/realsense_camera_test_rgbd_node.cpp similarity index 100% rename from camera/test/realsense_camera_test_rgbd_node.cpp rename to realsense_camera/test/realsense_camera_test_rgbd_node.cpp diff --git a/camera/test/realsense_camera_test_rgbd_node.h b/realsense_camera/test/realsense_camera_test_rgbd_node.h similarity index 100% rename from camera/test/realsense_camera_test_rgbd_node.h rename to realsense_camera/test/realsense_camera_test_rgbd_node.h diff --git a/camera/test/realsense_r200_color_only.test b/realsense_camera/test/realsense_r200_color_only.test similarity index 100% rename from camera/test/realsense_r200_color_only.test rename to realsense_camera/test/realsense_r200_color_only.test diff --git a/camera/test/realsense_r200_depth_only.test b/realsense_camera/test/realsense_r200_depth_only.test similarity index 100% rename from camera/test/realsense_r200_depth_only.test rename to realsense_camera/test/realsense_r200_depth_only.test diff --git a/camera/test/realsense_r200_dynamic_camera_options_params.launch b/realsense_camera/test/realsense_r200_dynamic_camera_options_params.launch similarity index 100% rename from camera/test/realsense_r200_dynamic_camera_options_params.launch rename to realsense_camera/test/realsense_r200_dynamic_camera_options_params.launch diff --git a/camera/test/realsense_r200_resolution.test b/realsense_camera/test/realsense_r200_resolution.test similarity index 100% rename from camera/test/realsense_r200_resolution.test rename to realsense_camera/test/realsense_r200_resolution.test diff --git a/camera/test/realsense_r200_rgbd.test b/realsense_camera/test/realsense_r200_rgbd.test similarity index 100% rename from camera/test/realsense_r200_rgbd.test rename to realsense_camera/test/realsense_r200_rgbd.test diff --git a/camera/test/realsense_r200_static_camera_options_params.launch b/realsense_camera/test/realsense_r200_static_camera_options_params.launch similarity index 100% rename from camera/test/realsense_r200_static_camera_options_params.launch rename to realsense_camera/test/realsense_r200_static_camera_options_params.launch diff --git a/camera/test/realsense_r200_stream_options_params.launch b/realsense_camera/test/realsense_r200_stream_options_params.launch similarity index 100% rename from camera/test/realsense_r200_stream_options_params.launch rename to realsense_camera/test/realsense_r200_stream_options_params.launch From 2e50e4fe92de57428dfeeb93d8e0a9d5f96b606a Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Fri, 6 May 2016 15:26:43 -0700 Subject: [PATCH 104/124] Fixed transformation origin bug for base frame to depth frame Negate y,z values in setOrigin of transform Changes the transform origin, negating the y, z values to remap from the camera frame orientation to the robots orientation --- realsense_camera/src/realsense_camera_nodelet.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/realsense_camera/src/realsense_camera_nodelet.cpp b/realsense_camera/src/realsense_camera_nodelet.cpp index b2df13dfbc..3a5a148ae1 100644 --- a/realsense_camera/src/realsense_camera_nodelet.cpp +++ b/realsense_camera/src/realsense_camera_nodelet.cpp @@ -936,7 +936,7 @@ namespace realsense_camera ros::Time time_stamp = ros::Time::now() + sleeper; // transform base frame to depth frame - tr.setOrigin(tf::Vector3(z_extrinsic.translation[0], z_extrinsic.translation[1], z_extrinsic.translation[2])); + tr.setOrigin(tf::Vector3(z_extrinsic.translation[2], -z_extrinsic.translation[0], -z_extrinsic.translation[1])); tr.setRotation(tf::Quaternion(0, 0, 0, 1)); tf_broadcaster.sendTransform(tf::StampedTransform(tr, time_stamp, base_frame_id_, depth_frame_id_)); From 2fec181be7493a0723266d2b7c80a69e809760d9 Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Mon, 16 May 2016 18:44:34 -0700 Subject: [PATCH 105/124] Added example for launching multiple cameras from a single launch file --- realsense_camera/README.md | 39 ++++++++++++------- ...realsense_r200_multiple_cameras.launch.xml | 29 ++++++++++++++ .../realsense_r200_multiple_cameras.launch | 25 ++++++++++++ 3 files changed, 78 insertions(+), 15 deletions(-) create mode 100644 realsense_camera/launch/includes/realsense_r200_multiple_cameras.launch.xml create mode 100644 realsense_camera/launch/realsense_r200_multiple_cameras.launch diff --git a/realsense_camera/README.md b/realsense_camera/README.md index b541db06cc..03a28446fd 100644 --- a/realsense_camera/README.md +++ b/realsense_camera/README.md @@ -6,7 +6,7 @@ | Kernel | 4.4.0-040400-generic | | Backend | video4linux | | ROS | indigo | -| librealsense | 0.9.1 | +| librealsense | 0.9.2 | | R200 Firmware | 1.0.72.06 | ###Installation @@ -183,7 +183,7 @@ Command to change dynamic parameters using commandline: ###Running the R200 nodelet - +####Getting Started Use the following command to launch the camera nodelet. You will notice the camera light up. $ roslaunch realsense_camera realsense_r200_nodelet_standalone_preset.launch @@ -223,11 +223,20 @@ For viewing supported camera settings with current values: $ rosservice call /camera/get_settings -For running multiple cameras simultaneously: -* Create ".launch" files similar to "realsense_r200_rgbd.launch" for each camera. - * Update the "camera" and "serial_no" arguments with unique values for each camera. - * You may choose to include (or not) the "processing.launch.xml" based on your requirement. -* Launch the ".launch" files for each camera in separate terminals. +####Launching Multiple Cameras +For running multiple cameras simultaneously: +Option 1: Using single nodelet manager for all the cameras +* Use "realsense_r200_multiple_cameras.launch". + * Update the "camera" and "serial_no" arguments with unique values for each camera. + "camera" should be a user friendly string that follows the ROS Names convention. (E.g. "camera1") + * For the "num_worker_threads" argument, allocate at least 1 thread for each camera. + +Option 2: Using separate nodelet manager for each camera +* Create ".launch" files similar to "realsense_r200_rgbd.launch" for each camera. + * Update the "camera" and "serial_no" arguments with unique values for each camera. + "camera" should be a user friendly string that follows the ROS Names convention. (E.g. "camera1") + * You may choose to include (or not) the "processing.launch.xml" based on your requirement. +* Launch the ".launch" files for each camera in separate terminals. ###Unit Tests The Unit Tests can be executed using either of the methods: @@ -274,12 +283,12 @@ The topic /camera/depth_registered/points, generated by launch file "realsense_r200_rgbd.launch", works best at 30 fps using 640x480 resolution on a system with 16GB of RAM. -* The camera does not provide hardware based depth registration/projector data. -Hence the launch file "realsense_r200_rgbd.launch" will not generate data for the following topics: - * /camera/depth_registered/hw_registered/image_rect_raw - * /camera/depth_registered/hw_registered/image_rect - * /camera/depth_registered/image - * /camera/depth/disparity - * /camera/depth_registered/disparity +* The camera does not provide hardware based depth registration/projector data. +Hence the launch file "realsense_r200_rgbd.launch" will not generate data for the following topics: + * /camera/depth_registered/hw_registered/image_rect_raw + * /camera/depth_registered/hw_registered/image_rect + * /camera/depth_registered/image + * /camera/depth/disparity + * /camera/depth_registered/disparity -* The performance benchmark for multiple cameras launched at the same time has not been defined yet. +* The performance benchmark for multiple cameras launched at the same time has not been defined yet. diff --git a/realsense_camera/launch/includes/realsense_r200_multiple_cameras.launch.xml b/realsense_camera/launch/includes/realsense_r200_multiple_cameras.launch.xml new file mode 100644 index 0000000000..0d14ff281e --- /dev/null +++ b/realsense_camera/launch/includes/realsense_r200_multiple_cameras.launch.xml @@ -0,0 +1,29 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/realsense_camera/launch/realsense_r200_multiple_cameras.launch b/realsense_camera/launch/realsense_r200_multiple_cameras.launch new file mode 100644 index 0000000000..3d49389203 --- /dev/null +++ b/realsense_camera/launch/realsense_r200_multiple_cameras.launch @@ -0,0 +1,25 @@ + + + + + + + + + + + + + + + + + + + + + + + + From 3249fcdd3ea7a30513dcbbfd6da6fbb56577d21e Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Tue, 24 May 2016 13:50:33 -0700 Subject: [PATCH 106/124] Added code to skip publishing duplicate frames for native streams --- .../src/realsense_camera_nodelet.cpp | 35 ++++++++++++------- .../src/realsense_camera_nodelet.h | 1 + 2 files changed, 24 insertions(+), 12 deletions(-) diff --git a/realsense_camera/src/realsense_camera_nodelet.cpp b/realsense_camera/src/realsense_camera_nodelet.cpp index 3a5a148ae1..5fc3f1dc83 100644 --- a/realsense_camera/src/realsense_camera_nodelet.cpp +++ b/realsense_camera/src/realsense_camera_nodelet.cpp @@ -80,6 +80,7 @@ namespace realsense_camera for (int i = 0; i < STREAM_COUNT; ++i) { camera_info_[i] = NULL; + stream_ts_[i] = -1; } ros::NodeHandle & nh = getNodeHandle(); @@ -765,21 +766,31 @@ namespace realsense_camera if (camera_publisher_[stream_index].getNumSubscribers() > 0 && rs_is_stream_enabled(rs_device_, (rs_stream) stream_index, 0) == 1) { - prepareStreamData ((rs_stream) stream_index); + int current_ts = rs_get_frame_timestamp(rs_device_, (rs_stream) stream_index, 0); + if (stream_ts_[stream_index] != current_ts) // publish frames only if its not duplicate + { + prepareStreamData((rs_stream) stream_index); - sensor_msgs::ImagePtr msg = cv_bridge::CvImage (std_msgs::Header(), - stream_encoding_[stream_index], - image_[stream_index]).toImageMsg(); + sensor_msgs::ImagePtr msg = cv_bridge::CvImage(std_msgs::Header(), + stream_encoding_[stream_index], + image_[stream_index]).toImageMsg(); - msg->header.frame_id = frame_id_[stream_index]; - msg->header.stamp = time_stamp_; // Publish timestamp to synchronize frames. - msg->width = image_[stream_index].cols; - msg->height = image_[stream_index].rows; - msg->is_bigendian = false; - msg->step = stream_step_[stream_index]; + msg->header.frame_id = frame_id_[stream_index]; + msg->header.stamp = time_stamp_; // Publish timestamp to synchronize frames. + msg->width = image_[stream_index].cols; + msg->height = image_[stream_index].rows; + msg->is_bigendian = false; + msg->step = stream_step_[stream_index]; - camera_info_ptr_[stream_index]->header.stamp = msg->header.stamp; - camera_publisher_[stream_index].publish (msg, camera_info_ptr_[stream_index]); + camera_info_ptr_[stream_index]->header.stamp = msg->header.stamp; + camera_publisher_[stream_index].publish (msg, camera_info_ptr_[stream_index]); + } + else + { + ROS_INFO_STREAM(nodelet_name_ << " - Duplicate frame for stream index " << stream_index << + " with ts = " << current_ts); + } + stream_ts_[stream_index] = current_ts; } } diff --git a/realsense_camera/src/realsense_camera_nodelet.h b/realsense_camera/src/realsense_camera_nodelet.h index 3cee0d2bfd..0e5121ecee 100644 --- a/realsense_camera/src/realsense_camera_nodelet.h +++ b/realsense_camera/src/realsense_camera_nodelet.h @@ -165,6 +165,7 @@ class RealsenseNodelet: public nodelet::Nodelet std::string mode_; std::map config_; int stream_step_[STREAM_COUNT]; + int stream_ts_[STREAM_COUNT]; struct CameraOptions { From 0d082dbe97b953bc9735a3bad412d084c3bca958 Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Wed, 25 May 2016 17:30:25 -0700 Subject: [PATCH 107/124] Added code to skip publishing PointCloud frame if Depth and/or Color has duplicate frames --- .../src/realsense_camera_nodelet.cpp | 18 +++++++++++------- 1 file changed, 11 insertions(+), 7 deletions(-) diff --git a/realsense_camera/src/realsense_camera_nodelet.cpp b/realsense_camera/src/realsense_camera_nodelet.cpp index 5fc3f1dc83..5782d2d725 100644 --- a/realsense_camera/src/realsense_camera_nodelet.cpp +++ b/realsense_camera/src/realsense_camera_nodelet.cpp @@ -759,6 +759,7 @@ namespace realsense_camera rs_wait_for_frames(rs_device_, &rs_error_); checkError(); time_stamp_ = ros::Time::now(); + bool duplicate_depth_color = false; for (int stream_index = 0; stream_index < STREAM_COUNT; ++stream_index) { @@ -767,7 +768,7 @@ namespace realsense_camera rs_is_stream_enabled(rs_device_, (rs_stream) stream_index, 0) == 1) { int current_ts = rs_get_frame_timestamp(rs_device_, (rs_stream) stream_index, 0); - if (stream_ts_[stream_index] != current_ts) // publish frames only if its not duplicate + if (stream_ts_[stream_index] != current_ts) // Publish frames only if its not duplicate { prepareStreamData((rs_stream) stream_index); @@ -787,25 +788,28 @@ namespace realsense_camera } else { - ROS_INFO_STREAM(nodelet_name_ << " - Duplicate frame for stream index " << stream_index << - " with ts = " << current_ts); + if ((stream_index == RS_STREAM_DEPTH) || (stream_index == RS_STREAM_COLOR)) + { + duplicate_depth_color = true; // Set this flag to true if Depth and/or Color frame is duplicate + } } stream_ts_[stream_index] = current_ts; } } if (pointcloud_publisher_.getNumSubscribers() > 0 && - rs_is_stream_enabled(rs_device_, RS_STREAM_DEPTH, 0) == 1 && enable_pointcloud_ == true) + rs_is_stream_enabled(rs_device_, RS_STREAM_DEPTH, 0) == 1 && enable_pointcloud_ == true && + (duplicate_depth_color == false)) // Skip publishing PointCloud if Depth and/or Color frame was duplicate { if (camera_publisher_[(uint32_t) RS_STREAM_DEPTH].getNumSubscribers() <= 0) { - prepareStreamData (RS_STREAM_DEPTH); + prepareStreamData(RS_STREAM_DEPTH); } if (camera_publisher_[(uint32_t) RS_STREAM_COLOR].getNumSubscribers() <= 0) { - prepareStreamData (RS_STREAM_COLOR); + prepareStreamData(RS_STREAM_COLOR); } - publishPointCloud (image_[(uint32_t) RS_STREAM_COLOR]); + publishPointCloud(image_[(uint32_t) RS_STREAM_COLOR]); } } } From f8b8a5a7792bc92e60bb94ee62c2ca0a542505b3 Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Wed, 1 Jun 2016 14:48:22 -0700 Subject: [PATCH 108/124] Updated artifacts to reflect 'stable' tag --- .github/ISSUE_TEMPLATE.md | 4 ++-- realsense_camera/README.md | 6 ++++-- 2 files changed, 6 insertions(+), 4 deletions(-) diff --git a/.github/ISSUE_TEMPLATE.md b/.github/ISSUE_TEMPLATE.md index e77dce1283..87a189d4f3 100644 --- a/.github/ISSUE_TEMPLATE.md +++ b/.github/ISSUE_TEMPLATE.md @@ -7,8 +7,8 @@ Please complete Your Configuration detail below. | Kernel | 4.4.0-040400-generic | ?-?-? | | Backend | video4linux | ? | | ROS | indigo | ? | -| ROS RealSense | Latest Release | ?.?.? | -| librealsense | 0.9.1 | ?.?.? | +| ROS RealSense | 'stable' Release | ?.?.? | +| librealsense | 0.9.2 | ?.?.? | | R200 Firmware | 1.0.72.06 | ?.?.?.? | --- diff --git a/realsense_camera/README.md b/realsense_camera/README.md index 03a28446fd..3759749776 100644 --- a/realsense_camera/README.md +++ b/realsense_camera/README.md @@ -19,8 +19,10 @@ If this does not work, you should first fix this issue before continuing with th #####Building package: -* Install ROS and create a local catkin workspace (see [wiki.ros.org](http://wiki.ros.org/) for instructions) -* Run `rosdep install realsense_camera` to install package dependencies +* Install ROS and create a local catkin workspace (see [wiki.ros.org](http://wiki.ros.org/) for instructions). +* Clone the source from https://github.com/intel-ros/realsense.git. + Checkout the 'stable' tag for the most stable version (E.g. `git checkout stable`). +* Run `rosdep install realsense_camera` to install package dependencies. * Compile the realsense_camera package by executing the `catkin_make` command. Successful execution of command will build target “realsense_camera_nodelet” From eecb459aa625239c7b143ee7521dda4149ddfdb7 Mon Sep 17 00:00:00 2001 From: Matthew Hansen Date: Thu, 26 May 2016 15:04:08 -0700 Subject: [PATCH 109/124] Added usb_port_id for selecting camera Adds usb_port_id as a launch param to select which camera to connect to by its usb port. See README for info. --- realsense_camera/README.md | 15 +++- ...realsense_r200_multiple_cameras.launch.xml | 46 +++++----- .../realsense_r200_nodelet.launch.xml | 40 +++++---- .../realsense_r200_multiple_cameras.launch | 11 ++- .../launch/realsense_r200_navigation.launch | 40 +++++---- ...ense_r200_nodelet_standalone_manual.launch | 64 +++++++------- ...ense_r200_nodelet_standalone_preset.launch | 40 +++++---- .../launch/realsense_r200_rgbd.launch | 11 ++- .../src/realsense_camera_nodelet.cpp | 86 ++++++++++--------- .../src/realsense_camera_nodelet.h | 3 +- 10 files changed, 191 insertions(+), 165 deletions(-) diff --git a/realsense_camera/README.md b/realsense_camera/README.md index 3759749776..5515fa3148 100644 --- a/realsense_camera/README.md +++ b/realsense_camera/README.md @@ -83,6 +83,10 @@ Infrared2 camera Specify the serial_no to uniquely connect to a camera, especially if multiple cameras are detected by the nodelet. You may get the serial_no from the info stream by launching "realsense_r200_nodelet_standalone_preset.launch" one at a time for each camera. + usb_port_id (string, default: blank) + Alternatively to serial_no, this can be used to connect to a camera by its USB Port ID, which is a + Bus Number-Port Number in the format "Bus#-Port#". If used with serial_no, both must match correctly for + camera to be connected. mode (string, default: preset) Specify the mode to start camera streams. Mode comprises of height, width and fps. Preset mode enables default values whereas Manual mode enables the specified parameter values. @@ -229,17 +233,20 @@ For viewing supported camera settings with current values: For running multiple cameras simultaneously: Option 1: Using single nodelet manager for all the cameras * Use "realsense_r200_multiple_cameras.launch". - * Update the "camera" and "serial_no" arguments with unique values for each camera. - "camera" should be a user friendly string that follows the ROS Names convention. (E.g. "camera1") * For the "num_worker_threads" argument, allocate at least 1 thread for each camera. Option 2: Using separate nodelet manager for each camera * Create ".launch" files similar to "realsense_r200_rgbd.launch" for each camera. - * Update the "camera" and "serial_no" arguments with unique values for each camera. - "camera" should be a user friendly string that follows the ROS Names convention. (E.g. "camera1") * You may choose to include (or not) the "processing.launch.xml" based on your requirement. * Launch the ".launch" files for each camera in separate terminals. + For either option you must: +* Update the "camera" and either the "serial_no" or "usb_port_id" argument with unique values for each camera. + * "camera" should be a user friendly string that follows the ROS Names convention. (E.g. "camera1") + * "serial_no" is the camera serial number and can be found by running the nodelet and viewing the terminal output + * "usb_port_id" is Bus Number-Port Number in "Bus#-Port#" format, and can be found by using `lsusb -t` + * if both "serial_no" and "usb_port_id" are set, both much match the same camera + ###Unit Tests The Unit Tests can be executed using either of the methods: diff --git a/realsense_camera/launch/includes/realsense_r200_multiple_cameras.launch.xml b/realsense_camera/launch/includes/realsense_r200_multiple_cameras.launch.xml index 0d14ff281e..f445177d5f 100644 --- a/realsense_camera/launch/includes/realsense_r200_multiple_cameras.launch.xml +++ b/realsense_camera/launch/includes/realsense_r200_multiple_cameras.launch.xml @@ -3,27 +3,29 @@ + - - - - - - - - - + + + + + + + + + + - - - - - - - - - - - - + + + + + + + + + + + + diff --git a/realsense_camera/launch/includes/realsense_r200_nodelet.launch.xml b/realsense_camera/launch/includes/realsense_r200_nodelet.launch.xml index 1d9eb43e70..c2b48d54b1 100644 --- a/realsense_camera/launch/includes/realsense_r200_nodelet.launch.xml +++ b/realsense_camera/launch/includes/realsense_r200_nodelet.launch.xml @@ -14,6 +14,7 @@ + @@ -29,31 +30,32 @@ + to generate point clouds. --> - - - - - - - - - - - - - - - + + + + + + + + + + + + + + + + - - + + @@ -65,4 +67,4 @@ - + diff --git a/realsense_camera/launch/realsense_r200_multiple_cameras.launch b/realsense_camera/launch/realsense_r200_multiple_cameras.launch index 3d49389203..d2ff3e6b98 100644 --- a/realsense_camera/launch/realsense_r200_multiple_cameras.launch +++ b/realsense_camera/launch/realsense_r200_multiple_cameras.launch @@ -1,25 +1,28 @@ - - - + + + - + + diff --git a/realsense_camera/launch/realsense_r200_navigation.launch b/realsense_camera/launch/realsense_r200_navigation.launch index 9ca8d38cb3..13cdde29ee 100644 --- a/realsense_camera/launch/realsense_r200_navigation.launch +++ b/realsense_camera/launch/realsense_r200_navigation.launch @@ -1,21 +1,23 @@ - - - - - - - - - - - - - - - - - + + + + + + + - + + + + + + + + + + + + + diff --git a/realsense_camera/launch/realsense_r200_nodelet_standalone_manual.launch b/realsense_camera/launch/realsense_r200_nodelet_standalone_manual.launch index e66365bba4..3b3a9b664d 100644 --- a/realsense_camera/launch/realsense_r200_nodelet_standalone_manual.launch +++ b/realsense_camera/launch/realsense_r200_nodelet_standalone_manual.launch @@ -1,34 +1,36 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - + + + + + + + + + + + + + - + + + + + + + + + + + + + + + + + + + diff --git a/realsense_camera/launch/realsense_r200_nodelet_standalone_preset.launch b/realsense_camera/launch/realsense_r200_nodelet_standalone_preset.launch index 186d2e12bf..45b4342151 100644 --- a/realsense_camera/launch/realsense_r200_nodelet_standalone_preset.launch +++ b/realsense_camera/launch/realsense_r200_nodelet_standalone_preset.launch @@ -1,21 +1,23 @@ - - - - - - - - - - - - - - - - - + + + + + + + - + + + + + + + + + + + + + diff --git a/realsense_camera/launch/realsense_r200_rgbd.launch b/realsense_camera/launch/realsense_r200_rgbd.launch index 91bdc887a4..9d3446429b 100644 --- a/realsense_camera/launch/realsense_r200_rgbd.launch +++ b/realsense_camera/launch/realsense_r200_rgbd.launch @@ -5,8 +5,9 @@ All topics are pushed down into the "camera" namespace, and it is prepended to tf frame ids. --> - - + + + @@ -28,8 +29,9 @@ - - + + + @@ -64,6 +66,7 @@ file="$(find realsense_camera)/launch/includes/realsense_r200_nodelet.launch.xml"> + diff --git a/realsense_camera/src/realsense_camera_nodelet.cpp b/realsense_camera/src/realsense_camera_nodelet.cpp index 5782d2d725..9dd94afd1d 100644 --- a/realsense_camera/src/realsense_camera_nodelet.cpp +++ b/realsense_camera/src/realsense_camera_nodelet.cpp @@ -131,6 +131,7 @@ namespace realsense_camera } else { + ROS_ERROR_STREAM(nodelet_name_ << " - Couldn't connect to camera! Shutting down..."); ros::shutdown(); } @@ -350,42 +351,47 @@ namespace realsense_camera return false; } - rs_device_ = getCameraBySerialNumber(); // Get rs_device_ using input serial number. - std::string detected_camera_msg = nodelet_name_ + " - Detected following cameras:"; - for (rs_device *rs_detected_device: rs_detected_devices_) - { - detected_camera_msg = detected_camera_msg + - "\n\t\t\t\t- Serial No: " + rs_get_device_serial(rs_detected_device, &rs_error_) + - "; Firmware: " + rs_get_device_firmware_version(rs_detected_device, &rs_error_) + - "; Name: " + rs_get_device_name(rs_detected_device, &rs_error_); - checkError(); - } - ROS_INFO_STREAM(detected_camera_msg); + // Print list of all cameras found + listCameras(); - // Exit with error if no serial number is specified and multiple cameras are detected. - if ((serial_no_.empty() == true) && (num_of_cameras_ > 1)) + // Exit with error if no serial number or usb_port_id is specified and multiple cameras are detected. + if (serial_no_.empty() && usb_port_id_.empty() && num_of_cameras_ > 1) { - ROS_ERROR_STREAM(nodelet_name_ << " - Multiple cameras detected but no input serial_no specified. Exiting!"); + ROS_ERROR_STREAM(nodelet_name_ << " - Multiple cameras detected but no input serial_no or usb_port_id specified. Exiting!"); return false; } - // Exit with error if no camera is detected that matches the input serial number. - if ((serial_no_.empty() != true) && (rs_device_ == NULL)) + // init rs_device_ before starting loop + rs_device_ = nullptr; + + // find camera + for (int i = 0; i < num_of_cameras_; i++) { - ROS_ERROR_STREAM(nodelet_name_ << " - No camera detected with input serial_no = " << serial_no_ << ". Exiting!"); - return false; + rs_device* rs_detected_device = rs_get_device(rs_context_, i, &rs_error_); + // check serial_no and usb_port_id + if ((serial_no_.empty() || serial_no_ == rs_get_device_serial(rs_detected_device, &rs_error_)) && + (usb_port_id_.empty() || usb_port_id_ == rs_get_device_usb_port_id(rs_detected_device, &rs_error_))) + { + // device found + rs_device_= rs_detected_device; + } + // continue loop } - // At this point, rs_device_ will be null if no input serial number was specified and only one camera is connected. - // This is a valid use case and the code will proceed. - if (rs_device_ == NULL) + if (rs_device_ == nullptr) { - rs_device_ = rs_get_device(rs_context_, 0, &rs_error_); - checkError(); + // camera not found + string error_msg = " - Couldn't find camera to connect with "; + error_msg += "serial_no = " + serial_no_ + ", "; + error_msg += "usb_port_id = " + usb_port_id_; + ROS_ERROR_STREAM(nodelet_name_ << error_msg); + return false; } + // print device info ROS_INFO_STREAM(nodelet_name_ << " - Connecting to camera with Serial No: " << - rs_get_device_serial(rs_device_, &rs_error_)); + rs_get_device_serial(rs_device_, &rs_error_) << + " USB Port ID: " << rs_get_device_usb_port_id(rs_device_, &rs_error_)); checkError(); // Enable streams. @@ -416,28 +422,23 @@ namespace realsense_camera return true; } - /* - * Returns the device details of the camera that matches the input serial_no. - * Returns NULL if no camera is found that matches the input serial_no. - * Also populates the list of detected cameras. - */ - rs_device * RealsenseNodelet::getCameraBySerialNumber() + void RealsenseNodelet::listCameras() { - rs_device *rs_device_detect; - rs_device *rs_device_connect = NULL; - for (int i = 0; i < num_of_cameras_; ++i) + // print list of detected cameras + std::string detected_camera_msg = " - Detected the following cameras:"; + for (int i = 0; i < num_of_cameras_; i++) { - rs_device_detect = rs_get_device(rs_context_, i, &rs_error_); - checkError(); - std::string device_serial_no = rs_get_device_serial(rs_device_detect, &rs_error_); + // get device + rs_device* rs_detected_device = rs_get_device(rs_context_, i, &rs_error_); + // print device details + detected_camera_msg = detected_camera_msg + + "\n\t\t\t\t- Serial No: " + rs_get_device_serial(rs_detected_device, &rs_error_) + + "; Firmware: " + rs_get_device_firmware_version(rs_detected_device, &rs_error_) + + "; Name: " + rs_get_device_name(rs_detected_device, &rs_error_) + + "; USB Port ID: " + rs_get_device_usb_port_id(rs_detected_device, &rs_error_); checkError(); - if (device_serial_no.compare(serial_no_) == 0) - { - rs_device_connect = rs_device_detect; - } - rs_detected_devices_.push_back(rs_device_detect); } - return rs_device_connect; + ROS_INFO_STREAM(nodelet_name_ + detected_camera_msg); } /* @@ -575,6 +576,7 @@ namespace realsense_camera void RealsenseNodelet::setStreamOptions() { pnh_.getParam("serial_no", serial_no_); + pnh_.getParam("usb_port_id", usb_port_id_); pnh_.param("camera", camera_, (std::string) R200); pnh_.param("mode", mode_, DEFAULT_MODE); pnh_.param("enable_depth", enable_depth_, ENABLE_DEPTH); diff --git a/realsense_camera/src/realsense_camera_nodelet.h b/realsense_camera/src/realsense_camera_nodelet.h index 0e5121ecee..c2866e3bae 100644 --- a/realsense_camera/src/realsense_camera_nodelet.h +++ b/realsense_camera/src/realsense_camera_nodelet.h @@ -119,6 +119,7 @@ class RealsenseNodelet: public nodelet::Nodelet int num_of_cameras_; std::string serial_no_; + std::string usb_port_id_; int color_height_; int color_width_; int depth_height_; @@ -191,12 +192,12 @@ class RealsenseNodelet: public nodelet::Nodelet void getCameraOptions(); void allocateResources(); bool connectToCamera(); - rs_device * getCameraBySerialNumber(); void fillStreamEncoding(); void setStreamOptions(); void setStaticCameraOptions(); bool getCameraOptionValues(realsense_camera::cameraConfiguration::Request & req, realsense_camera::cameraConfiguration::Response & res); void configCallback(realsense_camera::camera_paramsConfig &config, uint32_t level); + void listCameras(); }; } From f028b150ad163685ad4390ab9bdfd4aee333d00b Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Fri, 3 Jun 2016 11:09:22 -0700 Subject: [PATCH 110/124] Updated docs with Kinetic Kame details and for consistency --- .github/ISSUE_TEMPLATE.md | 22 +++--- realsense_camera/README.md | 133 +++++++++++++++++-------------------- 2 files changed, 71 insertions(+), 84 deletions(-) diff --git a/.github/ISSUE_TEMPLATE.md b/.github/ISSUE_TEMPLATE.md index 87a189d4f3..2e124d49f9 100644 --- a/.github/ISSUE_TEMPLATE.md +++ b/.github/ISSUE_TEMPLATE.md @@ -1,15 +1,15 @@ ### System Configuration -Please complete Your Configuration detail below. - -| Version | Best Known | Your Configuration | -|:---------------- |:---------------------|:---------------------| -| Operating System | Ubuntu 14.04.4 LTS | ? ? ? | -| Kernel | 4.4.0-040400-generic | ?-?-? | -| Backend | video4linux | ? | -| ROS | indigo | ? | -| ROS RealSense | 'stable' Release | ?.?.? | -| librealsense | 0.9.2 | ?.?.? | -| R200 Firmware | 1.0.72.06 | ?.?.?.? | +Please complete Your Configuration detail below. Refer to the BKC at [Configuration](../realsense_camera/README.md#configuration). + +| Version | Your Configuration | +|:---------------- |:---------------------| +| Operating System | ? ? ? | +| Kernel | ?-?-? | +| Backend | ? | +| ROS | ? | +| ROS RealSense | ?.?.? | +| librealsense | ?.?.? | +| R200 Firmware | ?.?.?.? | --- #### How to collect Configuration Data diff --git a/realsense_camera/README.md b/realsense_camera/README.md index 5515fa3148..2dfe8cf1bf 100644 --- a/realsense_camera/README.md +++ b/realsense_camera/README.md @@ -1,15 +1,14 @@ #Intel® RealSense™ Technology - ROS Integration -###Configuration -| Version | Best Known | -|:---------------- |:---------------------| -| Operating System | Ubuntu 14.04.4 LTS | -| Kernel | 4.4.0-040400-generic | -| Backend | video4linux | -| ROS | indigo | -| librealsense | 0.9.2 | -| R200 Firmware | 1.0.72.06 | - -###Installation +###Configuration: +| Version | Best Known (indigo) | Best Known (kinetic) | +|:---------------- |:---------------------|:---------------------| +| Operating System | Ubuntu 14.04.4 LTS | Ubuntu 16.04 LTS | +| Kernel | 4.4.0-040400-generic | 4.4.0-22-generic | +| Backend | video4linux | video4linux | +| librealsense | 0.9.2 | 0.9.2 | +| R200 Firmware | 1.0.72.06 | 1.0.72.06 | + +###Installation: #####Getting the camera to work on Linux * Clone the source from the librealsense git repository https://github.com/IntelRealSense/librealsense.git and follow the "Installation Guide" for installing the library. @@ -17,32 +16,27 @@ If this does not work, you should first fix this issue before continuing with the ROS integration. * Make sure "/usr/local/lib" is set in your "LD_LIBRARY_PATH". -#####Building package: +#####Building the package * Install ROS and create a local catkin workspace (see [wiki.ros.org](http://wiki.ros.org/) for instructions). * Clone the source from https://github.com/intel-ros/realsense.git. Checkout the 'stable' tag for the most stable version (E.g. `git checkout stable`). * Run `rosdep install realsense_camera` to install package dependencies. * Compile the realsense_camera package by executing the `catkin_make` command. + Successful execution of command will build target “realsense_camera_nodelet” -Successful execution of command will build target “realsense_camera_nodelet” +Sample launch files are available in "realsense_camera/launch" directory +* realsense_r200_rgbd.launch +* realsense_r200_nodelet_standalone_preset.launch +* realsense_r200_nodelet_standalone_manual.launch +* realsense_r200_multiple_cameras.launch -Sample launch files are available in camera/launch directory +###Package Features: -realsense_r200_rgbd.launch - -realsense_r200_nodelet_standalone_preset.launch - -realsense_r200_nodelet_standalone_manual.launch - -### Intel® RealSense™ R200 Nodelet -Publishing stream data from the Intel® RealSense™ R200 (DS4) camera - -#### Subscribed Topics +####Subscribed Topics None -#### Published Topics (default) - +####Published Topics (default) Color camera camera/color/image_raw (sensor_msgs/Image) @@ -71,12 +65,16 @@ Infrared2 camera camera/infrared2/camera_info Calibration data -#### Transform Frames - The following command creates a pdf file that describes the transforms generated by the camera nodelet. You may refer to the [ROS tf wiki](http://wiki.ros.org/tf) for more commands. +####Services + get_settings (camera/get_settings) + Gets the current value of the supported camera options in "options:value" format separated by semicolon. +####Transform Frames rosrun tf tf_monitor + Creates a pdf file that describes the transforms generated by the camera nodelet. + You may refer to the [ROS tf wiki](http://wiki.ros.org/tf) for more commands. -#### Static Parameters +####Static Parameters Stream parameters: serial_no (string, default: blank) @@ -87,27 +85,27 @@ Infrared2 camera Alternatively to serial_no, this can be used to connect to a camera by its USB Port ID, which is a Bus Number-Port Number in the format "Bus#-Port#". If used with serial_no, both must match correctly for camera to be connected. - mode (string, default: preset) - Specify the mode to start camera streams. Mode comprises of height, width and fps. - Preset mode enables default values whereas Manual mode enables the specified parameter values. - color_height (int, default: 480) - Specify the color camera height resolution. - color_width (int, default: 640) - Specify the color camera width resolution. - depth_height (int, default: 360) - Specify the depth camera height resolution. - depth_width (int, default: 480) - Specify the depth camera width resolution. - color_fps (int, default: 60) - Specify the color camera FPS - depth_fps (int, default: 60) - Specify the depth camera FPS - enable_color (bool, default: true) - Specify if to enable or not the color camera. - enable_pointcloud (bool, default: true) - Specify if to enable or not the point cloud camera. - enable_tf (bool, default: true) - Specify if to enable or not the transform frames. + mode (string, default: preset) + Specify the mode to start camera streams. Mode comprises of height, width and fps. + Preset mode enables default values whereas Manual mode enables the specified parameter values. + color_height (int, default: 480) + Specify the color camera height resolution. + color_width (int, default: 640) + Specify the color camera width resolution. + depth_height (int, default: 360) + Specify the depth camera height resolution. + depth_width (int, default: 480) + Specify the depth camera width resolution. + color_fps (int, default: 60) + Specify the color camera FPS + depth_fps (int, default: 60) + Specify the depth camera FPS + enable_color (bool, default: true) + Specify if to enable or not the color camera. + enable_pointcloud (bool, default: true) + Specify if to enable or not the point cloud camera. + enable_tf (bool, default: true) + Specify if to enable or not the transform frames. base_frame_id (string, default: camera_link) Specify the base frame id of the camera. depth_frame_id (string, default: camera_depth_frame) @@ -122,8 +120,8 @@ Infrared2 camera Specify the IR frame id of the camera. ir2_frame_id (string, default: camera_infrared2_frame) Specify the IR2 frame id of the camera. - camera (string, default: "R200") - Specify the camera name. + camera (string, default: "R200") + Specify the camera name. Camera parameters: Following are the parameters that can be set only statically in the R200 camera: r200_depth_units : [1, 2147483647] @@ -140,11 +138,6 @@ Infrared2 camera r200_depth_control_neighbor_threshold : [0 - 1023] r200_depth_control_lr_threshold : [0 - 2047] -####Services - get_settings (camera/get_settings) - -To get supported camera options with current value set. It returns string in options:value format where different options are seperated by semicolon. - ####Dynamic Parameters Stream parameters: @@ -188,7 +181,7 @@ Command to change dynamic parameters using commandline: E.g. $ rosrun dynamic_reconfigure dynparam set /RealsenseNodelet color_backlight_compensation 2 -###Running the R200 nodelet +###Running the R200 nodelet: ####Getting Started Use the following command to launch the camera nodelet. You will notice the camera light up. @@ -247,38 +240,32 @@ For running multiple cameras simultaneously: * "usb_port_id" is Bus Number-Port Number in "Bus#-Port#" format, and can be found by using `lsusb -t` * if both "serial_no" and "usb_port_id" are set, both much match the same camera -###Unit Tests +###Unit Tests: The Unit Tests can be executed using either of the methods: -Using rostest command with test files +Using `rostest` command with test files $ rostest realsense_camera E.g. rostest realsense_camera realsense_r200_depth_only.test -Using rosrun command +Using `rosrun` command $ roslaunch realsense_camera realsense_r200_nodelet_standalone_manual.launch $ rosrun realsense_camera realsense_camera_test E.g. rosrun realsense_camera realsense_camera_test enable_depth 1 depth_encoding 16UC1 depth_height 360 depth_width 480 depth_step 960 enable_color 1 color_encoding rgb8 color_height 480 color_width 640 color_step 1920 -Sample test files are available in test directory - -realsense_r200_rgbd.test - -realsense_r200_color_only.test +Both these methods first starts the nodelet and then executes all the unit tests. -realsense_r200_depth_only.test - -realsense_r200_resolution.test - - -Both of these methods first starts "RealsenseNodelet" for Intel® RealSense™ R200 (DS4) camera and then executes all the unit tests. +Sample test files are available in "realsense_camera/test" directory +* realsense_r200_rgbd.test +* realsense_r200_color_only.test +* realsense_r200_depth_only.test +* realsense_r200_resolution.test ###Developer API: Refer to the function definitions in [realsense_camera_nodelet.h](src/realsense_camera_nodelet.h) - ###Limitations: * Currently, the camera nodelet has been tested to work only for R200 cameras. From ff729121b9f3ecf44e15dbf5d296f4e2040739df Mon Sep 17 00:00:00 2001 From: Mark D Horn Date: Fri, 3 Jun 2016 16:38:17 -0700 Subject: [PATCH 111/124] Fix white space issues in test files --- .../test/realsense_r200_color_only.test | 17 +++++++------ .../test/realsense_r200_depth_only.test | 17 +++++++------ .../test/realsense_r200_resolution.test | 24 +++++++++---------- .../test/realsense_r200_rgbd.test | 5 ++-- 4 files changed, 30 insertions(+), 33 deletions(-) diff --git a/realsense_camera/test/realsense_r200_color_only.test b/realsense_camera/test/realsense_r200_color_only.test index 99150176ac..29f001c030 100644 --- a/realsense_camera/test/realsense_r200_color_only.test +++ b/realsense_camera/test/realsense_r200_color_only.test @@ -1,10 +1,9 @@ - - - - - - - - + + + + + + + diff --git a/realsense_camera/test/realsense_r200_depth_only.test b/realsense_camera/test/realsense_r200_depth_only.test index 66423cc13e..205ae84195 100644 --- a/realsense_camera/test/realsense_r200_depth_only.test +++ b/realsense_camera/test/realsense_r200_depth_only.test @@ -1,10 +1,9 @@ - - - - - - - - + + + + + + + diff --git a/realsense_camera/test/realsense_r200_resolution.test b/realsense_camera/test/realsense_r200_resolution.test index 65d893ed8d..8477438e6e 100644 --- a/realsense_camera/test/realsense_r200_resolution.test +++ b/realsense_camera/test/realsense_r200_resolution.test @@ -1,14 +1,14 @@ - - - - - - - - - - - + + + + + + + + + + + diff --git a/realsense_camera/test/realsense_r200_rgbd.test b/realsense_camera/test/realsense_r200_rgbd.test index 8832e12d12..2713f936d0 100644 --- a/realsense_camera/test/realsense_r200_rgbd.test +++ b/realsense_camera/test/realsense_r200_rgbd.test @@ -3,6 +3,5 @@ - - - + + From f8a96b25e7ec012ca385b92994d3dc1c0abcef96 Mon Sep 17 00:00:00 2001 From: rjingar Date: Thu, 9 Jun 2016 16:11:06 -0700 Subject: [PATCH 112/124] Refactored test code to remove code duplication --- .../test/realsense_camera_test_node.cpp | 535 ++++++++---------- .../test/realsense_camera_test_node.h | 136 ++--- 2 files changed, 304 insertions(+), 367 deletions(-) diff --git a/realsense_camera/test/realsense_camera_test_node.cpp b/realsense_camera/test/realsense_camera_test_node.cpp index f514370b88..6908baf48f 100644 --- a/realsense_camera/test/realsense_camera_test_node.cpp +++ b/realsense_camera/test/realsense_camera_test_node.cpp @@ -32,7 +32,36 @@ #include "realsense_camera_test_node.h" using namespace std; -void imageInfrared1Callback(const sensor_msgs::ImageConstPtr & msg, const sensor_msgs::CameraInfoConstPtr & info_msg) + +void getMsgInfo(rs_stream stream, const sensor_msgs::ImageConstPtr &msg) +{ + g_encoding_recv[stream] = msg->encoding; + g_width_recv[stream] = msg->width; + g_height_recv[stream] = msg->height; + g_step_recv[stream] = msg->step; +} + +void getCameraInfo(rs_stream stream, const sensor_msgs::CameraInfoConstPtr &info_msg) +{ + g_caminfo_height_recv[stream] = info_msg->height; + g_caminfo_width_recv[stream] = info_msg->width; + + g_dmodel_recv[stream] = info_msg->distortion_model; + + // copy rotation matrix + for (unsigned int i = 0; i < sizeof(info_msg->R)/sizeof(double); i++) + { + g_caminfo_rotation_recv[stream][i] = info_msg->R[i]; + } + + // copy projection matrix + for (unsigned int i = 0; i < sizeof(info_msg->P)/sizeof(double); i++) + { + g_caminfo_projection_recv[stream][i] = info_msg->P[i]; + } +} + +void imageInfrared1Callback(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &info_msg) { cv::Mat image = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::TYPE_8UC1)->image; @@ -49,33 +78,18 @@ void imageInfrared1Callback(const sensor_msgs::ImageConstPtr & msg, const sensor } infrared1_data++; } - infrared1_avg = infrared1_total / infrared1_count; - - infrared1_encoding_recv = msg->encoding; - infrared1_width_recv = msg->width; - infrared1_height_recv = msg->height; - infrared1_step_recv = msg->step; - - inf1_caminfo_height_recv = info_msg->height; - inf1_caminfo_width_recv = info_msg->width; - inf1_dmodel_recv = info_msg->distortion_model; - - // copy rotation matrix - for (unsigned int i = 0; i < sizeof(info_msg->R)/sizeof(double); i++) + if (infrared1_count != 0) { - inf1_caminfo_rotation_recv[i] = info_msg->R[i]; + g_infrared1_avg = infrared1_total / infrared1_count; } - // copy projection matrix - for (unsigned int i = 0; i < sizeof(info_msg->P)/sizeof(double); i++) - { - inf1_caminfo_projection_recv[i] = info_msg->P[i]; - } + getMsgInfo(RS_STREAM_INFRARED, msg); + getCameraInfo(RS_STREAM_INFRARED, info_msg); - infrared1_recv = true; + g_infrared1_recv = true; } -void imageInfrared2Callback(const sensor_msgs::ImageConstPtr & msg, const sensor_msgs::CameraInfoConstPtr & info_msg) +void imageInfrared2Callback(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &info_msg) { cv::Mat image = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::TYPE_8UC1)->image; @@ -92,33 +106,18 @@ void imageInfrared2Callback(const sensor_msgs::ImageConstPtr & msg, const sensor } infrared2_data++; } - infrared2_avg = infrared2_total / infrared2_count; - - infrared2_encoding_recv = msg->encoding; - infrared2_width_recv = msg->width; - infrared2_height_recv = msg->height; - infrared2_step_recv = msg->step; - - inf2_caminfo_height_recv = info_msg->height; - inf2_caminfo_width_recv = info_msg->width; - inf2_dmodel_recv = info_msg->distortion_model; - - // copy rotation matrix - for (unsigned int i = 0; i < sizeof(info_msg->R)/sizeof(double); i++) + if (infrared2_count != 0) { - inf2_caminfo_rotation_recv[i] = info_msg->R[i]; + g_infrared2_avg = infrared2_total / infrared2_count; } - // copy projection matrix - for (unsigned int i = 0; i < sizeof(info_msg->P)/sizeof(double); i++) - { - inf2_caminfo_projection_recv[i] = info_msg->P[i]; - } + getMsgInfo(RS_STREAM_INFRARED2, msg); + getCameraInfo(RS_STREAM_INFRARED2, info_msg); - infrared2_recv = true; + g_infrared2_recv = true; } -void imageDepthCallback(const sensor_msgs::ImageConstPtr & msg, const sensor_msgs::CameraInfoConstPtr & info_msg) +void imageDepthCallback(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &info_msg) { cv::Mat image = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::TYPE_16UC1)->image; uint16_t *image_data = (uint16_t *) image.data; @@ -136,34 +135,17 @@ void imageDepthCallback(const sensor_msgs::ImageConstPtr & msg, const sensor_msg } if (depth_count != 0) { - depth_avg = depth_total / depth_count; + g_depth_avg = depth_total / depth_count; } - depth_encoding_recv = msg->encoding; - depth_height_recv = msg->height; - depth_width_recv = msg->width; - depth_step_recv = msg->step; + getMsgInfo(RS_STREAM_DEPTH, msg); + getCameraInfo(RS_STREAM_DEPTH, info_msg); - depth_caminfo_height_recv = info_msg->height; - depth_caminfo_width_recv = info_msg->width; - depth_dmodel_recv = info_msg->distortion_model; - - // copy rotation matrix - for (unsigned int i = 0; i < sizeof(info_msg->R)/sizeof(double); i++) - { - depth_caminfo_rotation_recv[i] = info_msg->R[i]; - } - // copy projection matrix - for (unsigned int i = 0; i < sizeof(info_msg->P)/sizeof(double); i++) - { - depth_caminfo_projection_recv[i] = info_msg->P[i]; - } - - depth_recv = true; + g_depth_recv = true; } - void pcCallback(const sensor_msgs::PointCloud2ConstPtr pc) +void pcCallback(const sensor_msgs::PointCloud2ConstPtr pc) { pcl::PointCloud < pcl::PointXYZRGB > pointcloud; pcl::fromROSMsg(*pc, pointcloud); @@ -180,17 +162,16 @@ void imageDepthCallback(const sensor_msgs::ImageConstPtr & msg, const sensor_msg pc_depth_count++; } } - if (pc_depth_count != 0) { - pc_depth_avg = pc_depth_total / pc_depth_count; + g_pc_depth_avg = pc_depth_total / pc_depth_count; } - pc_recv = true; + g_pc_recv = true; } -void imageColorCallback(const sensor_msgs::ImageConstPtr & msg, const sensor_msgs::CameraInfoConstPtr & info_msg) +void imageColorCallback(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &info_msg) { cv::Mat image = cv_bridge::toCvShare(msg, "rgb8")->image; @@ -206,107 +187,92 @@ void imageColorCallback(const sensor_msgs::ImageConstPtr & msg, const sensor_msg } color_data++; } - color_avg = color_total / color_count; - - color_encoding_recv = msg->encoding; - color_height_recv = msg->height; - color_width_recv = msg->width; - color_step_recv = msg->step; - - color_caminfo_height_recv = info_msg->height; - color_caminfo_width_recv = info_msg->width; - color_dmodel_recv = info_msg->distortion_model; - - // copy rotation matrix - for (unsigned int i = 0; i < sizeof(info_msg->R)/sizeof(double); i++) + if (color_count != 0) { - color_caminfo_rotation_recv[i] = info_msg->R[i]; + g_color_avg = color_total / color_count; } - // copy projection matrix - for (unsigned int i = 0; i < sizeof(info_msg->P)/sizeof(double); i++) - { - color_caminfo_projection_recv[i] = info_msg->P[i]; - } + getMsgInfo(RS_STREAM_COLOR, msg); + getCameraInfo(RS_STREAM_COLOR, info_msg); for (unsigned int i = 0; i < 5; i++) { - color_caminfo_D_recv[i] = info_msg->D[i]; + g_color_caminfo_D_recv[i] = info_msg->D[i]; } - color_recv = true; + g_color_recv = true; } -TEST (RealsenseTests, testColorStream) +TEST(RealsenseTests, testColorStream) { - if (enable_color) + if (g_enable_color) { - EXPECT_TRUE (color_avg > 0); - EXPECT_TRUE (color_recv); + EXPECT_TRUE(g_color_avg > 0); + EXPECT_TRUE(g_color_recv); - if (!color_encoding_exp.empty ()) + if (!g_color_encoding_exp.empty ()) { - EXPECT_EQ (color_encoding_exp, color_encoding_recv); + EXPECT_EQ(g_color_encoding_exp, g_encoding_recv[RS_STREAM_COLOR]); } - if (color_step_exp > 0) + if (g_color_step_exp > 0) { - EXPECT_EQ (color_step_exp, color_step_recv); + EXPECT_EQ(g_color_step_exp, g_step_recv[RS_STREAM_COLOR]); } } else { - EXPECT_FALSE (color_recv); + EXPECT_FALSE(g_color_recv); } } -TEST (RealsenseTests, testColorResolution) +TEST(RealsenseTests, testColorResolution) { - if (enable_color) + if (g_enable_color) { - if (color_height_exp > 0) + if (g_color_height_exp > 0) { - EXPECT_EQ (color_height_exp, color_height_recv); + EXPECT_EQ(g_color_height_exp, g_height_recv[RS_STREAM_COLOR]); } - if (color_width_exp > 0) + if (g_color_width_exp > 0) { - EXPECT_EQ (color_width_exp, color_width_recv); + EXPECT_EQ(g_color_width_exp, g_width_recv[RS_STREAM_COLOR]); } } } -TEST (RealsenseTests, testColorCameraInfo) +TEST(RealsenseTests, testColorCameraInfo) { - if (enable_color) + if (g_enable_color) { - EXPECT_EQ (color_width_recv, color_caminfo_width_recv); - EXPECT_EQ (color_height_recv, color_caminfo_height_recv); - EXPECT_STREQ (color_dmodel_recv.c_str (), "plumb_bob"); + EXPECT_EQ(g_width_recv[RS_STREAM_COLOR], g_caminfo_width_recv[RS_STREAM_COLOR]); + EXPECT_EQ(g_height_recv[RS_STREAM_COLOR], g_caminfo_height_recv[RS_STREAM_COLOR]); + EXPECT_STREQ(g_dmodel_recv[RS_STREAM_COLOR].c_str(), "plumb_bob"); // verify rotation is equal to identity matrix for (unsigned int i = 0; i < sizeof(ROTATION_IDENTITY)/sizeof(double); i++) { - EXPECT_EQ (ROTATION_IDENTITY[i], color_caminfo_rotation_recv[i]); + EXPECT_EQ(ROTATION_IDENTITY[i], g_caminfo_rotation_recv[RS_STREAM_COLOR][i]); } // check projection matrix values are set - EXPECT_TRUE(color_caminfo_projection_recv[0] != (double) 0); - EXPECT_EQ(color_caminfo_projection_recv[1], (double) 0); - EXPECT_TRUE(color_caminfo_projection_recv[2] != (double) 0); - EXPECT_EQ(color_caminfo_projection_recv[3], (double) 0); - EXPECT_EQ(color_caminfo_projection_recv[4], (double) 0); - EXPECT_TRUE(color_caminfo_projection_recv[5] != (double) 0); - EXPECT_TRUE(color_caminfo_projection_recv[6] != (double) 0); - EXPECT_EQ(color_caminfo_projection_recv[7], (double) 0); - EXPECT_EQ(color_caminfo_projection_recv[8], (double) 0); - EXPECT_EQ(color_caminfo_projection_recv[9], (double) 0); - EXPECT_TRUE(color_caminfo_projection_recv[10] != (double) 0); - EXPECT_EQ(color_caminfo_projection_recv[11], (double) 0); + EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_COLOR][0] != (double) 0); + EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_COLOR][1], (double) 0); + EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_COLOR][2] != (double) 0); + EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_COLOR][3], (double) 0); + EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_COLOR][4], (double) 0); + EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_COLOR][5] != (double) 0); + EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_COLOR][6] != (double) 0); + EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_COLOR][7], (double) 0); + EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_COLOR][8], (double) 0); + EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_COLOR][9], (double) 0); + EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_COLOR][10] != (double) 0); + EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_COLOR][11], (double) 0); float color_caminfo_D = 1; // ignoring the 5th value since it always appears to be 0.0 on tested R200 cameras for (unsigned int i = 0; i < 4; i++) { - color_caminfo_D = color_caminfo_D && color_caminfo_D_recv[i]; + color_caminfo_D = color_caminfo_D && g_color_caminfo_D_recv[i]; } EXPECT_TRUE(color_caminfo_D != (float) 0); @@ -314,232 +280,229 @@ TEST (RealsenseTests, testColorCameraInfo) } } -TEST (RealsenseTests, testIsDepthStreamEnabled) +TEST(RealsenseTests, testIsDepthStreamEnabled) { - if (enable_depth) + if (g_enable_depth) { - EXPECT_TRUE (depth_recv); - EXPECT_TRUE (infrared1_recv); - EXPECT_TRUE (infrared2_recv); + EXPECT_TRUE(g_depth_recv); + EXPECT_TRUE(g_infrared1_recv); + EXPECT_TRUE(g_infrared2_recv); } else { - EXPECT_FALSE (depth_recv); - EXPECT_FALSE (infrared1_recv); - EXPECT_FALSE (infrared2_recv); + EXPECT_FALSE(g_depth_recv); + EXPECT_FALSE(g_infrared1_recv); + EXPECT_FALSE(g_infrared2_recv); } } -TEST (RealsenseTests, testDepthStream) +TEST(RealsenseTests, testDepthStream) { - if (enable_depth) + if (g_enable_depth) { - ROS_INFO_STREAM ("RealSense Camera - depth_avg: " << depth_avg << " mm"); - EXPECT_TRUE (depth_avg > 0); - EXPECT_TRUE (depth_recv); - if (!depth_encoding_exp.empty ()) + ROS_INFO_STREAM("RealSense Camera - depth_avg: " << g_depth_avg << " mm"); + EXPECT_TRUE(g_depth_avg > 0); + EXPECT_TRUE(g_depth_recv); + if (!g_depth_encoding_exp.empty ()) { - EXPECT_EQ (depth_encoding_exp, depth_encoding_recv); + EXPECT_EQ(g_depth_encoding_exp, g_encoding_recv[RS_STREAM_DEPTH]); } - if (depth_step_exp > 0) + if (g_depth_step_exp > 0) { - EXPECT_EQ (depth_step_exp, depth_step_recv); + EXPECT_EQ(g_depth_step_exp, g_step_recv[RS_STREAM_DEPTH]); } } else { - EXPECT_FALSE (depth_recv); + EXPECT_FALSE(g_depth_recv); } } -TEST (RealsenseTests, testDepthResolution) +TEST(RealsenseTests, testDepthResolution) { - if (enable_depth) + if (g_enable_depth) { - if (depth_height_exp > 0) + if (g_depth_height_exp > 0) { - EXPECT_EQ (depth_height_exp, depth_height_recv); + EXPECT_EQ(g_depth_height_exp, g_height_recv[RS_STREAM_DEPTH]); } - if (depth_width_exp > 0) + if (g_depth_width_exp > 0) { - EXPECT_EQ (depth_width_exp, depth_width_recv); + EXPECT_EQ(g_depth_width_exp, g_width_recv[RS_STREAM_DEPTH]); } } } -TEST (RealsenseTests, testDepthCameraInfo) +TEST(RealsenseTests, testDepthCameraInfo) { - if (enable_depth) + if (g_enable_depth) { - EXPECT_EQ (depth_width_recv, depth_caminfo_width_recv); - EXPECT_EQ (depth_height_recv, depth_caminfo_height_recv); - EXPECT_STREQ (depth_dmodel_recv.c_str (), "plumb_bob"); + EXPECT_EQ(g_width_recv[RS_STREAM_DEPTH], g_caminfo_width_recv[RS_STREAM_DEPTH]); + EXPECT_EQ(g_height_recv[RS_STREAM_DEPTH], g_caminfo_height_recv[RS_STREAM_DEPTH]); + EXPECT_STREQ(g_dmodel_recv[RS_STREAM_DEPTH].c_str (), "plumb_bob"); // verify rotation is equal to identity matrix for (unsigned int i = 0; i < sizeof(ROTATION_IDENTITY)/sizeof(double); i++) { - EXPECT_EQ (ROTATION_IDENTITY[i], depth_caminfo_rotation_recv[i]); + EXPECT_EQ(ROTATION_IDENTITY[i], g_caminfo_rotation_recv[RS_STREAM_DEPTH][i]); } // check projection matrix values are set - EXPECT_TRUE(depth_caminfo_projection_recv[0] != (double) 0); - EXPECT_EQ(depth_caminfo_projection_recv[1], (double) 0); - EXPECT_TRUE(depth_caminfo_projection_recv[2] != (double) 0); - EXPECT_TRUE(depth_caminfo_projection_recv[3] != (double) 0); - EXPECT_EQ(depth_caminfo_projection_recv[4], (double) 0); - EXPECT_TRUE(depth_caminfo_projection_recv[5] != (double) 0); - EXPECT_TRUE(depth_caminfo_projection_recv[6] != (double) 0); - EXPECT_TRUE(depth_caminfo_projection_recv[7] != (double) 0); - EXPECT_EQ(depth_caminfo_projection_recv[8], (double) 0); - EXPECT_EQ(depth_caminfo_projection_recv[9], (double) 0); - EXPECT_TRUE(depth_caminfo_projection_recv[10] != (double) 0); - EXPECT_TRUE(depth_caminfo_projection_recv[11] != (double) 0); - + EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_DEPTH][0] != (double) 0); + EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_DEPTH][1], (double) 0); + EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_DEPTH][2] != (double) 0); + EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_DEPTH][3] != (double) 0); + EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_DEPTH][4], (double) 0); + EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_DEPTH][5] != (double) 0); + EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_DEPTH][6] != (double) 0); + EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_DEPTH][7] != (double) 0); + EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_DEPTH][8], (double) 0); + EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_DEPTH][9], (double) 0); + EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_DEPTH][10] != (double) 0); + EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_DEPTH][11] != (double) 0); } } -TEST (RealsenseTests, testInfrared1Stream) +TEST(RealsenseTests, testInfrared1Stream) { - if (enable_depth) + if (g_enable_depth) { - EXPECT_TRUE (infrared1_avg > 0); - EXPECT_TRUE (infrared1_recv); - if (!infrared1_encoding_exp.empty ()) + EXPECT_TRUE(g_infrared1_avg > 0); + EXPECT_TRUE(g_infrared1_recv); + if (!g_infrared1_encoding_exp.empty ()) { - EXPECT_EQ (infrared1_encoding_exp, infrared1_encoding_recv); + EXPECT_EQ(g_infrared1_encoding_exp, g_encoding_recv[RS_STREAM_INFRARED]); } - if (infrared1_step_exp > 0) + if (g_infrared1_step_exp > 0) { - EXPECT_EQ (infrared1_step_exp, infrared1_step_recv); + EXPECT_EQ(g_infrared1_step_exp, g_step_recv[RS_STREAM_INFRARED]); } } else { - EXPECT_FALSE (infrared1_recv); + EXPECT_FALSE(g_infrared1_recv); } } -TEST (RealsenseTests, testInfrared1Resolution) +TEST(RealsenseTests, testInfrared1Resolution) { - if (enable_depth) + if (g_enable_depth) { - if (depth_width_exp > 0) + if (g_depth_width_exp > 0) { - EXPECT_EQ (depth_width_exp, infrared1_width_recv); + EXPECT_EQ(g_depth_width_exp, g_width_recv[RS_STREAM_INFRARED]); } - if (depth_height_exp > 0) + if (g_depth_height_exp > 0) { - EXPECT_EQ (depth_height_exp, infrared1_height_recv); + EXPECT_EQ(g_depth_height_exp, g_height_recv[RS_STREAM_INFRARED]); } } } -TEST (RealsenseTests, testInfrared1CameraInfo) +TEST(RealsenseTests, testInfrared1CameraInfo) { - if (enable_depth) + if (g_enable_depth) { - EXPECT_EQ (infrared1_width_recv, inf1_caminfo_width_recv); - EXPECT_EQ (infrared1_height_recv, inf1_caminfo_height_recv); - EXPECT_STREQ (inf1_dmodel_recv.c_str (), "plumb_bob"); + EXPECT_EQ(g_width_recv[RS_STREAM_INFRARED], g_caminfo_width_recv[RS_STREAM_INFRARED]); + EXPECT_EQ(g_height_recv[RS_STREAM_INFRARED], g_caminfo_height_recv[RS_STREAM_INFRARED]); + EXPECT_STREQ(g_dmodel_recv[RS_STREAM_INFRARED].c_str (), "plumb_bob"); // verify rotation is equal to identity matrix for (unsigned int i = 0; i < sizeof(ROTATION_IDENTITY)/sizeof(double); i++) { - EXPECT_EQ (ROTATION_IDENTITY[i], inf1_caminfo_rotation_recv[i]); + EXPECT_EQ(ROTATION_IDENTITY[i], g_caminfo_rotation_recv[RS_STREAM_INFRARED][i]); } // check projection matrix values are set - EXPECT_TRUE(inf1_caminfo_projection_recv[0] != (double) 0); - EXPECT_EQ(inf1_caminfo_projection_recv[1], (double) 0); - EXPECT_TRUE(inf1_caminfo_projection_recv[2] != (double) 0); - EXPECT_EQ(inf1_caminfo_projection_recv[3], (double) 0); - EXPECT_EQ(inf1_caminfo_projection_recv[4], (double) 0); - EXPECT_TRUE(inf1_caminfo_projection_recv[5] != (double) 0); - EXPECT_TRUE(inf1_caminfo_projection_recv[6] != (double) 0); - EXPECT_EQ(inf1_caminfo_projection_recv[7], (double) 0); - EXPECT_EQ(inf1_caminfo_projection_recv[8], (double) 0); - EXPECT_EQ(inf1_caminfo_projection_recv[9], (double) 0); - EXPECT_TRUE(inf1_caminfo_projection_recv[10] != (double) 0); - EXPECT_EQ(inf1_caminfo_projection_recv[11], (double) 0); - + EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_INFRARED][0] != (double) 0); + EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_INFRARED][1], (double) 0); + EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_INFRARED][2] != (double) 0); + EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_INFRARED][3], (double) 0); + EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_INFRARED][4], (double) 0); + EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_INFRARED][5] != (double) 0); + EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_INFRARED][6] != (double) 0); + EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_INFRARED][7], (double) 0); + EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_INFRARED][8], (double) 0); + EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_INFRARED][9], (double) 0); + EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_INFRARED][10] != (double) 0); + EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_INFRARED][11], (double) 0); } } -TEST (RealsenseTests, testInfrared2Stream) +TEST(RealsenseTests, testInfrared2Stream) { - if (enable_depth) + if (g_enable_depth) { - EXPECT_TRUE (infrared2_avg > 0); - EXPECT_TRUE (infrared2_recv); + EXPECT_TRUE(g_infrared2_avg > 0); + EXPECT_TRUE(g_infrared2_recv); } else { - EXPECT_FALSE (infrared2_recv); + EXPECT_FALSE(g_infrared2_recv); } } -TEST (RealsenseTests, testInfrared2Resolution) +TEST(RealsenseTests, testInfrared2Resolution) { - if (enable_depth) + if (g_enable_depth) { - if (depth_width_exp > 0) + if (g_depth_width_exp > 0) { - EXPECT_EQ (depth_width_exp, infrared2_width_recv); + EXPECT_EQ(g_depth_width_exp, g_width_recv[RS_STREAM_INFRARED2]); } - if (depth_height_exp > 0) + if (g_depth_height_exp > 0) { - EXPECT_EQ (depth_height_exp, infrared2_height_recv); + EXPECT_EQ(g_depth_height_exp, g_height_recv[RS_STREAM_INFRARED2]); } } } -TEST (RealsenseTests, testInfrared2CameraInfo) +TEST(RealsenseTests, testInfrared2CameraInfo) { - if (enable_depth) + if (g_enable_depth) { - EXPECT_EQ (infrared2_width_recv, inf2_caminfo_width_recv); - EXPECT_EQ (infrared2_height_recv, inf2_caminfo_height_recv); - EXPECT_STREQ (inf2_dmodel_recv.c_str (), "plumb_bob"); + EXPECT_EQ(g_width_recv[RS_STREAM_INFRARED2], g_caminfo_width_recv[RS_STREAM_INFRARED2]); + EXPECT_EQ(g_height_recv[RS_STREAM_INFRARED2], g_caminfo_height_recv[RS_STREAM_INFRARED2]); + EXPECT_STREQ(g_dmodel_recv[RS_STREAM_INFRARED2].c_str (), "plumb_bob"); // verify rotation is equal to identity matrix for (unsigned int i = 0; i < sizeof(ROTATION_IDENTITY)/sizeof(double); i++) { - EXPECT_EQ (ROTATION_IDENTITY[i], inf2_caminfo_rotation_recv[i]); + EXPECT_EQ(ROTATION_IDENTITY[i], g_caminfo_rotation_recv[RS_STREAM_INFRARED2][i]); } // check projection matrix values are set - EXPECT_TRUE(inf2_caminfo_projection_recv[0] != (double) 0); - EXPECT_EQ(inf2_caminfo_projection_recv[1], (double) 0); - EXPECT_TRUE(inf2_caminfo_projection_recv[2] != (double) 0); - EXPECT_EQ(inf2_caminfo_projection_recv[3], (double) 0); - EXPECT_EQ(inf2_caminfo_projection_recv[4], (double) 0); - EXPECT_TRUE(inf2_caminfo_projection_recv[5] != (double) 0); - EXPECT_TRUE(inf2_caminfo_projection_recv[6] != (double) 0); - EXPECT_EQ(inf2_caminfo_projection_recv[7], (double) 0); - EXPECT_EQ(inf2_caminfo_projection_recv[8], (double) 0); - EXPECT_EQ(inf2_caminfo_projection_recv[9], (double) 0); - EXPECT_TRUE(inf2_caminfo_projection_recv[10] != (double) 0); - EXPECT_EQ(inf2_caminfo_projection_recv[11], (double) 0); - + EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_INFRARED2][0] != (double) 0); + EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_INFRARED2][1], (double) 0); + EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_INFRARED2][2] != (double) 0); + EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_INFRARED2][3], (double) 0); + EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_INFRARED2][4], (double) 0); + EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_INFRARED2][5] != (double) 0); + EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_INFRARED2][6] != (double) 0); + EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_INFRARED2][7], (double) 0); + EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_INFRARED2][8], (double) 0); + EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_INFRARED2][9], (double) 0); + EXPECT_TRUE(g_caminfo_projection_recv[RS_STREAM_INFRARED2][10] != (double) 0); + EXPECT_EQ(g_caminfo_projection_recv[RS_STREAM_INFRARED2][11], (double) 0); } } - TEST (RealsenseTests, testPointCloud) + TEST(RealsenseTests, testPointCloud) { - if (enable_depth) + if (g_enable_depth) { - ROS_INFO_STREAM ("RealSense Camera - pc_depth_avg: " << pc_depth_avg); - EXPECT_TRUE (pc_depth_avg > 0); - EXPECT_TRUE (pc_recv); + ROS_INFO_STREAM("RealSense Camera - pc_depth_avg: " << g_pc_depth_avg); + EXPECT_TRUE(g_pc_depth_avg > 0); + EXPECT_TRUE(g_pc_recv); } else { - EXPECT_FALSE (pc_recv); + EXPECT_FALSE(g_pc_recv); } } -TEST (RealsenseTests, testTransforms) +TEST(RealsenseTests, testTransforms) { // make sure all transforms are being broadcast as expected tf::TransformListener tf_listener; @@ -550,9 +513,9 @@ TEST (RealsenseTests, testTransforms) EXPECT_TRUE(tf_listener.waitForTransform (COLOR_OPTICAL_DEF_FRAME, COLOR_DEF_FRAME, ros::Time(0), ros::Duration(3.0))); } -TEST (RealsenseTests, testCameraOptions) +TEST(RealsenseTests, testCameraOptions) { - stringstream settings_ss (srv.response.configuration_str); + stringstream settings_ss (g_srv.response.configuration_str); string setting; string setting_name; string setting_value; @@ -562,11 +525,11 @@ TEST (RealsenseTests, testCameraOptions) stringstream setting_ss (setting); getline (setting_ss, setting_name, ':'); setting_value = (setting.substr (setting.rfind (":") + 1)); - if (config_args.find (setting_name) != config_args.end ()) + if (g_config_args.find (setting_name) != g_config_args.end ()) { int actual_value = atoi (setting_value.c_str ()); - int expected_value = atoi (config_args.at (setting_name).c_str ()); - EXPECT_EQ (expected_value, actual_value); + int expected_value = atoi (g_config_args.at (setting_name).c_str ()); + EXPECT_EQ(expected_value, actual_value); } } } @@ -581,7 +544,7 @@ void fillConfigMap(int argc, char **argv) } while (args.size() > 1) { - config_args[args[0]] = args[1]; + g_config_args[args[0]] = args[1]; args.erase(args.begin()); args.erase(args.begin()); @@ -590,71 +553,71 @@ void fillConfigMap(int argc, char **argv) if (argc > 1) { // Set depth arguments. - if (config_args.find("enable_depth") != config_args.end()) + if (g_config_args.find("enable_depth") != g_config_args.end()) { - ROS_INFO ("RealSense Camera - Setting %s to %s", "enable_depth", config_args.at("enable_depth").c_str()); - if (strcmp((config_args.at("enable_depth").c_str ()),"true") == 0) + ROS_INFO("RealSense Camera - Setting %s to %s", "enable_depth", g_config_args.at("enable_depth").c_str()); + if (strcmp((g_config_args.at("enable_depth").c_str ()),"true") == 0) { - enable_depth = true; + g_enable_depth = true; } else { - enable_depth = false; + g_enable_depth = false; } } - if (config_args.find("depth_encoding") != config_args.end()) + if (g_config_args.find("depth_encoding") != g_config_args.end()) { - ROS_INFO ("RealSense Camera - Setting %s to %s", "depth_encoding", config_args.at("depth_encoding").c_str()); - depth_encoding_exp = config_args.at("depth_encoding").c_str(); + ROS_INFO("RealSense Camera - Setting %s to %s", "depth_encoding", g_config_args.at("depth_encoding").c_str()); + g_depth_encoding_exp = g_config_args.at("depth_encoding").c_str(); } - if (config_args.find("depth_height") != config_args.end()) + if (g_config_args.find("depth_height") != g_config_args.end()) { - ROS_INFO ("RealSense Camera - Setting %s to %s", "depth_height", config_args.at("depth_height").c_str()); - depth_height_exp = atoi(config_args.at("depth_height").c_str()); + ROS_INFO("RealSense Camera - Setting %s to %s", "depth_height", g_config_args.at("depth_height").c_str()); + g_depth_height_exp = atoi(g_config_args.at("depth_height").c_str()); } - if (config_args.find("depth_width") != config_args.end()) + if (g_config_args.find("depth_width") != g_config_args.end()) { - ROS_INFO ("RealSense Camera - Setting %s to %s", "depth_width", config_args.at("depth_width").c_str()); - depth_width_exp = atoi(config_args.at("depth_width").c_str()); + ROS_INFO("RealSense Camera - Setting %s to %s", "depth_width", g_config_args.at("depth_width").c_str()); + g_depth_width_exp = atoi(g_config_args.at("depth_width").c_str()); } - if (config_args.find("depth_step") != config_args.end()) + if (g_config_args.find("depth_step") != g_config_args.end()) { - ROS_INFO ("RealSense Camera - Setting %s to %s", "depth_step", config_args.at("depth_step").c_str()); - depth_step_exp = atoi(config_args.at("depth_step").c_str()); + ROS_INFO("RealSense Camera - Setting %s to %s", "depth_step", g_config_args.at("depth_step").c_str()); + g_depth_step_exp = atoi(g_config_args.at("depth_step").c_str()); } // Set color arguments. - if (config_args.find("enable_color") != config_args.end()) + if (g_config_args.find("enable_color") != g_config_args.end()) { - ROS_INFO ("RealSense Camera - Setting %s to %s", "enable_color", config_args.at("enable_color").c_str()); - if (strcmp((config_args.at("enable_color").c_str ()),"true") == 0) + ROS_INFO("RealSense Camera - Setting %s to %s", "enable_color", g_config_args.at("enable_color").c_str()); + if (strcmp((g_config_args.at("enable_color").c_str ()),"true") == 0) { - enable_color = true; + g_enable_color = true; } else { - enable_color = false; + g_enable_color = false; } } - if (config_args.find("color_encoding") != config_args.end()) + if (g_config_args.find("color_encoding") != g_config_args.end()) { - ROS_INFO ("RealSense Camera - Setting %s to %s", "color_encoding", config_args.at("color_encoding").c_str()); - color_encoding_exp = config_args.at("color_encoding").c_str(); + ROS_INFO("RealSense Camera - Setting %s to %s", "color_encoding", g_config_args.at("color_encoding").c_str()); + g_color_encoding_exp = g_config_args.at("color_encoding").c_str(); } - if (config_args.find("color_height") != config_args.end()) + if (g_config_args.find("color_height") != g_config_args.end()) { - ROS_INFO ("RealSense Camera - Setting %s to %s", "color_height", config_args.at("color_height").c_str()); - color_height_exp = atoi(config_args.at("color_height").c_str()); + ROS_INFO("RealSense Camera - Setting %s to %s", "color_height", g_config_args.at("color_height").c_str()); + g_color_height_exp = atoi(g_config_args.at("color_height").c_str()); } - if (config_args.find("color_width") != config_args.end()) + if (g_config_args.find("color_width") != g_config_args.end()) { - ROS_INFO ("RealSense Camera - Setting %s to %s", "color_width", config_args.at("color_width").c_str()); - color_width_exp = atoi(config_args.at("color_width").c_str()); + ROS_INFO("RealSense Camera - Setting %s to %s", "color_width", g_config_args.at("color_width").c_str()); + g_color_width_exp = atoi(g_config_args.at("color_width").c_str()); } - if (config_args.find("color_step") != config_args.end()) + if (g_config_args.find("color_step") != g_config_args.end()) { - ROS_INFO ("RealSense Camera - Setting %s to %s", "color_step", config_args.at("color_step").c_str()); - color_step_exp = atoi(config_args.at("color_step").c_str()); + ROS_INFO("RealSense Camera - Setting %s to %s", "color_step", g_config_args.at("color_step").c_str()); + g_color_step_exp = atoi(g_config_args.at("color_step").c_str()); } } } @@ -665,21 +628,21 @@ int main(int argc, char **argv) ros::init(argc, argv, "utest"); fillConfigMap(argc, argv); - ROS_INFO_STREAM ("RealSense Camera - Starting Tests..."); + ROS_INFO_STREAM("RealSense Camera - Starting Tests..."); ros::NodeHandle nh; image_transport::ImageTransport it(nh); - camera_subscriber[0] = it.subscribeCamera(DEPTH_TOPIC, 1, imageDepthCallback, 0); - camera_subscriber[1] = it.subscribeCamera(COLOR_TOPIC, 1, imageColorCallback, 0); - camera_subscriber[2] = it.subscribeCamera(IR1_TOPIC, 1, imageInfrared1Callback, 0); - if (camera.find(R200) != std::string::npos) + g_camera_subscriber[0] = it.subscribeCamera(DEPTH_TOPIC, 1, imageDepthCallback, 0); + g_camera_subscriber[1] = it.subscribeCamera(COLOR_TOPIC, 1, imageColorCallback, 0); + g_camera_subscriber[2] = it.subscribeCamera(IR1_TOPIC, 1, imageInfrared1Callback, 0); + if (g_camera.find(R200) != std::string::npos) { - camera_subscriber[3] = it.subscribeCamera(IR2_TOPIC, 1, imageInfrared2Callback, 0); + g_camera_subscriber[3] = it.subscribeCamera(IR2_TOPIC, 1, imageInfrared2Callback, 0); } - m_sub_pc = nh.subscribe (PC_TOPIC, 1, pcCallback); + g_sub_pc = nh.subscribe (PC_TOPIC, 1, pcCallback); ros::ServiceClient client = nh.serviceClient < realsense_camera::cameraConfiguration > (SETTINGS_SERVICE); - client.call(srv); + client.call(g_srv); ros::Duration duration; duration.sec = 10; diff --git a/realsense_camera/test/realsense_camera_test_node.h b/realsense_camera/test/realsense_camera_test_node.h index b70cba4359..a2bb912e80 100644 --- a/realsense_camera/test/realsense_camera_test_node.h +++ b/realsense_camera/test/realsense_camera_test_node.h @@ -51,6 +51,9 @@ #include #include #include +#include + +#define R200_STREAMS_COUNT 4 const char *DEPTH_TOPIC = "camera/depth/image_raw"; const char *COLOR_TOPIC = "camera/color/image_raw"; @@ -69,84 +72,55 @@ const char *COLOR_OPTICAL_DEF_FRAME = "camera_rgb_optical_frame"; const double ROTATION_IDENTITY[] = {1, 0, 0, 0, 1, 0, 0, 0, 1}; //utest commandline args -int color_height_exp = 0; -int color_width_exp = 0; -int depth_height_exp = 0; -int depth_width_exp = 0; -uint32_t depth_step_exp; // Expected depth step. -uint32_t color_step_exp; // Expected color step. -uint32_t infrared1_step_exp; // Expected infrared1 step. -uint32_t infrared2_step_exp; // Expected infrared2 step. - -bool enable_color = true; -bool enable_depth = true; -bool enable_pointcloud = true; - -std::string depth_encoding_exp; // Expected depth encoding. -std::string color_encoding_exp; // Expected color encoding. -std::string infrared1_encoding_exp; // Expected infrared1 encoding. -std::string infrared2_encoding_exp; // Expected infrared2 encoding. - -image_transport::CameraSubscriber camera_subscriber[4]; -ros::Subscriber m_sub_pc; - -std::map config_args; - -bool depth_recv = false; -bool color_recv = false; -bool infrared1_recv = false; -bool infrared2_recv = false; -bool pc_recv = false; - -float depth_avg = 0; -float color_avg = 0; -float infrared1_avg = 0; -float infrared2_avg = 0; -float pc_depth_avg = 0; - -int depth_height_recv = 0; -int depth_width_recv = 0; -int color_height_recv = 0; -int color_width_recv = 0; -int infrared1_width_recv = 0; -int infrared1_height_recv = 0; -int infrared2_width_recv = 0; -int infrared2_height_recv = 0; - -uint32_t depth_step_recv = 0; // Received depth step. -uint32_t color_step_recv = 0; // Received depth step. -uint32_t infrared1_step_recv = 0; // Received depth step. -uint32_t infrared2_step_recv = 0; // Received depth step. - -std::string depth_encoding_recv; // Expected depth encoding. -std::string infrared1_encoding_recv; // Expected depth encoding. -std::string infrared2_encoding_recv; // Expected depth encoding. -std::string color_encoding_recv; // Expected color encoding. - - -int depth_caminfo_height_recv = 0; -int depth_caminfo_width_recv = 0; -double depth_caminfo_rotation_recv[9] = {0}; -double depth_caminfo_projection_recv[12] = {0}; -int color_caminfo_height_recv = 0; -int color_caminfo_width_recv = 0; -double color_caminfo_rotation_recv[9] = {0}; -double color_caminfo_projection_recv[12] = {0}; -float color_caminfo_D_recv[5] = {0}; -int inf1_caminfo_height_recv = 0; -int inf1_caminfo_width_recv = 0; -double inf1_caminfo_rotation_recv[9] = {0}; -double inf1_caminfo_projection_recv[12] = {0}; -int inf2_caminfo_height_recv = 0; -int inf2_caminfo_width_recv = 0; -double inf2_caminfo_rotation_recv[9] = {0}; -double inf2_caminfo_projection_recv[12] = {0}; - -std::string inf1_dmodel_recv; -std::string inf2_dmodel_recv; -std::string depth_dmodel_recv; -std::string color_dmodel_recv; -std::string camera = "R200"; - -realsense_camera::cameraConfiguration srv; - +int g_color_height_exp = 0; +int g_color_width_exp = 0; +int g_depth_height_exp = 0; +int g_depth_width_exp = 0; +uint32_t g_depth_step_exp; // Expected depth step. +uint32_t g_color_step_exp; // Expected color step. +uint32_t g_infrared1_step_exp; // Expected infrared1 step. +uint32_t g_infrared2_step_exp; // Expected infrared2 step. + +bool g_enable_color = true; +bool g_enable_depth = true; +bool g_enable_pointcloud = true; + +std::string g_depth_encoding_exp; // Expected depth encoding. +std::string g_color_encoding_exp; // Expected color encoding. +std::string g_infrared1_encoding_exp; // Expected infrared1 encoding. +std::string g_infrared2_encoding_exp; // Expected infrared2 encoding. + +image_transport::CameraSubscriber g_camera_subscriber[R200_STREAMS_COUNT]; +ros::Subscriber g_sub_pc; + +std::map g_config_args; + +bool g_depth_recv = false; +bool g_color_recv = false; +bool g_infrared1_recv = false; +bool g_infrared2_recv = false; +bool g_pc_recv = false; + +float g_depth_avg = 0; +float g_color_avg = 0; +float g_infrared1_avg = 0; +float g_infrared2_avg = 0; +float g_pc_depth_avg = 0; + +int g_height_recv[R200_STREAMS_COUNT] = {0}; +int g_width_recv[R200_STREAMS_COUNT] = {0}; +uint32_t g_step_recv[R200_STREAMS_COUNT] = {0}; // Received stream step. + +std::string g_encoding_recv[R200_STREAMS_COUNT]; // Expected stream encoding. + +int g_caminfo_height_recv[R200_STREAMS_COUNT] = {0}; +int g_caminfo_width_recv[R200_STREAMS_COUNT] = {0}; +float g_color_caminfo_D_recv[5] = {0}; + +double g_caminfo_rotation_recv[R200_STREAMS_COUNT][9] = {0}; +double g_caminfo_projection_recv[R200_STREAMS_COUNT][12] = {0}; + +std::string g_dmodel_recv[R200_STREAMS_COUNT]; +std::string g_camera = "R200"; + +realsense_camera::cameraConfiguration g_srv; From d3aaa561f56755442de0f0141f48d3e1b4f66ee1 Mon Sep 17 00:00:00 2001 From: Matthew Hansen Date: Tue, 14 Jun 2016 15:33:00 -0700 Subject: [PATCH 113/124] Refactored R200 code into derived class Refactors the code to create an R200 derived class and moves R200 logic out of base class --- realsense_camera/CMakeLists.txt | 4 +- realsense_camera/README.md | 4 +- ...mera_params.cfg => camera_params_r200.cfg} | 2 +- ...realsense_r200_multiple_cameras.launch.xml | 2 +- .../realsense_r200_nodelet.launch.xml | 2 +- .../launch/realsense_r200_navigation.launch | 2 +- ...ense_r200_nodelet_standalone_manual.launch | 2 +- ...ense_r200_nodelet_standalone_preset.launch | 2 +- .../realsense_camera_nodelet_plugins.xml | 4 +- .../src/realsense_camera_nodelet.cpp | 419 +++++------------- .../src/realsense_camera_nodelet.h | 267 ++++++----- .../src/realsense_camera_nodelet_r200.cpp | 285 ++++++++++++ .../src/realsense_camera_nodelet_r200.h | 73 +++ 13 files changed, 615 insertions(+), 453 deletions(-) rename realsense_camera/cfg/{camera_params.cfg => camera_params_r200.cfg} (97%) create mode 100644 realsense_camera/src/realsense_camera_nodelet_r200.cpp create mode 100644 realsense_camera/src/realsense_camera_nodelet_r200.h diff --git a/realsense_camera/CMakeLists.txt b/realsense_camera/CMakeLists.txt index b786807405..99bf966986 100644 --- a/realsense_camera/CMakeLists.txt +++ b/realsense_camera/CMakeLists.txt @@ -40,14 +40,14 @@ generate_messages( #add dynamic reconfigure api generate_dynamic_reconfigure_options( - cfg/camera_params.cfg + cfg/camera_params_r200.cfg ) include_directories( ${catkin_INCLUDE_DIRS} ) -add_library(realsense_camera_nodelet src/realsense_camera_nodelet.cpp) +add_library(realsense_camera_nodelet src/realsense_camera_nodelet.cpp src/realsense_camera_nodelet_r200.cpp) target_link_libraries(realsense_camera_nodelet ${catkin_LIBRARIES} realsense diff --git a/realsense_camera/README.md b/realsense_camera/README.md index 2dfe8cf1bf..3c9c60a6eb 100644 --- a/realsense_camera/README.md +++ b/realsense_camera/README.md @@ -178,7 +178,7 @@ Command to launch GUI: Command to change dynamic parameters using commandline: $ rosrun dynamic_reconfigure dynparam set / - E.g. $ rosrun dynamic_reconfigure dynparam set /RealsenseNodelet color_backlight_compensation 2 + E.g. $ rosrun dynamic_reconfigure dynparam set /RealsenseNodeletR200 color_backlight_compensation 2 ###Running the R200 nodelet: @@ -186,6 +186,8 @@ Command to change dynamic parameters using commandline: Use the following command to launch the camera nodelet. You will notice the camera light up. $ roslaunch realsense_camera realsense_r200_nodelet_standalone_preset.launch + +If you would like to create or use your own launch files, the nodelet name for the R200 camera is RealsenseNodeletR200. See the sample launch files for examples of how to launch the nodelet. View using RVIZ: diff --git a/realsense_camera/cfg/camera_params.cfg b/realsense_camera/cfg/camera_params_r200.cfg similarity index 97% rename from realsense_camera/cfg/camera_params.cfg rename to realsense_camera/cfg/camera_params_r200.cfg index 8619283ba5..496e9f9c2e 100755 --- a/realsense_camera/cfg/camera_params.cfg +++ b/realsense_camera/cfg/camera_params_r200.cfg @@ -27,4 +27,4 @@ gen.add("r200_auto_exposure_bottom_edge", int_t, 0, "Auto Exp gen.add("r200_auto_exposure_left_edge", int_t, 0, "Auto Exposure Left Edge", 0, 0, 639) gen.add("r200_auto_exposure_right_edge", int_t, 0, "Auto Exposure Right Edge", 639, 0, 639) -exit(gen.generate(PACKAGE, "realsense_camera", "camera_params")) +exit(gen.generate(PACKAGE, "realsense_camera", "camera_params_r200")) diff --git a/realsense_camera/launch/includes/realsense_r200_multiple_cameras.launch.xml b/realsense_camera/launch/includes/realsense_r200_multiple_cameras.launch.xml index f445177d5f..bf1b5f5336 100644 --- a/realsense_camera/launch/includes/realsense_r200_multiple_cameras.launch.xml +++ b/realsense_camera/launch/includes/realsense_r200_multiple_cameras.launch.xml @@ -6,7 +6,7 @@ + args="load realsense_camera/RealsenseNodeletR200 $(arg manager)"> diff --git a/realsense_camera/launch/includes/realsense_r200_nodelet.launch.xml b/realsense_camera/launch/includes/realsense_r200_nodelet.launch.xml index c2b48d54b1..2b0e7fef03 100644 --- a/realsense_camera/launch/includes/realsense_r200_nodelet.launch.xml +++ b/realsense_camera/launch/includes/realsense_r200_nodelet.launch.xml @@ -35,7 +35,7 @@ + args="load realsense_camera/RealsenseNodeletR200 $(arg manager)"> diff --git a/realsense_camera/launch/realsense_r200_navigation.launch b/realsense_camera/launch/realsense_r200_navigation.launch index 13cdde29ee..bff55143e0 100644 --- a/realsense_camera/launch/realsense_r200_navigation.launch +++ b/realsense_camera/launch/realsense_r200_navigation.launch @@ -10,7 +10,7 @@ + args="load realsense_camera/RealsenseNodeletR200 standalone_nodelet" > diff --git a/realsense_camera/launch/realsense_r200_nodelet_standalone_manual.launch b/realsense_camera/launch/realsense_r200_nodelet_standalone_manual.launch index 3b3a9b664d..6169769da4 100644 --- a/realsense_camera/launch/realsense_r200_nodelet_standalone_manual.launch +++ b/realsense_camera/launch/realsense_r200_nodelet_standalone_manual.launch @@ -17,7 +17,7 @@ + args="load realsense_camera/RealsenseNodeletR200 standalone_nodelet"> diff --git a/realsense_camera/launch/realsense_r200_nodelet_standalone_preset.launch b/realsense_camera/launch/realsense_r200_nodelet_standalone_preset.launch index 45b4342151..ccda09f5c6 100644 --- a/realsense_camera/launch/realsense_r200_nodelet_standalone_preset.launch +++ b/realsense_camera/launch/realsense_r200_nodelet_standalone_preset.launch @@ -10,7 +10,7 @@ + args="load realsense_camera/RealsenseNodeletR200 standalone_nodelet"> diff --git a/realsense_camera/realsense_camera_nodelet_plugins.xml b/realsense_camera/realsense_camera_nodelet_plugins.xml index 1a835a54d4..c62d71c5dd 100644 --- a/realsense_camera/realsense_camera_nodelet_plugins.xml +++ b/realsense_camera/realsense_camera_nodelet_plugins.xml @@ -1,7 +1,7 @@ - + - Intel(R) RealSense(TM) Camera nodelet. + Intel(R) RealSense(TM) R200 Camera nodelet. diff --git a/realsense_camera/src/realsense_camera_nodelet.cpp b/realsense_camera/src/realsense_camera_nodelet.cpp index 9dd94afd1d..2b4ff383cd 100644 --- a/realsense_camera/src/realsense_camera_nodelet.cpp +++ b/realsense_camera/src/realsense_camera_nodelet.cpp @@ -33,10 +33,6 @@ using namespace cv; using namespace std; -// Nodelet dependencies. -#include -#include - PLUGINLIB_EXPORT_CLASS (realsense_camera::RealsenseNodelet, nodelet::Nodelet) namespace realsense_camera { @@ -46,7 +42,7 @@ namespace realsense_camera */ RealsenseNodelet::~RealsenseNodelet() { - device_thread_->join(); + stream_thread_->join(); if (enable_tf_ == true) { @@ -67,50 +63,35 @@ namespace realsense_camera } /* - * Initialize the realsense code. + * Initialize the realsense camera */ void RealsenseNodelet::onInit() { - nodelet_name_ = getName(); // Get the nodelet name - ROS_INFO_STREAM(nodelet_name_ << " - Starting..."); - // Set default configurations. is_device_started_ = false; - for (int i = 0; i < STREAM_COUNT; ++i) + for (int i = 0; i < num_streams_; ++i) { camera_info_[i] = NULL; stream_ts_[i] = -1; } - ros::NodeHandle & nh = getNodeHandle(); - pnh_ = getPrivateNodeHandle(); - - // Set up the topics. - image_transport::ImageTransport it (nh); - setStreamOptions(); + // Set up the topics. frame_id_[RS_STREAM_DEPTH] = depth_optical_frame_id_; frame_id_[RS_STREAM_COLOR] = color_optical_frame_id_; frame_id_[RS_STREAM_INFRARED] = ir_frame_id_; - frame_id_[RS_STREAM_INFRARED2] = ir2_frame_id_; // Advertise the various topics and services. + image_transport::ImageTransport it (nh_); camera_publisher_[RS_STREAM_COLOR] = it.advertiseCamera(COLOR_TOPIC, 1); camera_publisher_[RS_STREAM_DEPTH] = it.advertiseCamera(DEPTH_TOPIC, 1); camera_publisher_[RS_STREAM_INFRARED] = it.advertiseCamera(IR1_TOPIC, 1); - if (camera_.find (R200) != std::string::npos) - { - camera_publisher_[RS_STREAM_INFRARED2] = it.advertiseCamera(IR2_TOPIC, 1); - } - - pointcloud_publisher_ = nh.advertise(PC_TOPIC, 1); - - get_options_service_ = nh.advertiseService(SETTINGS_SERVICE, &RealsenseNodelet::getCameraOptionValues, this); + pointcloud_publisher_ = nh_.advertise(PC_TOPIC, 1); - dynamic_reconf_server_.reset(new dynamic_reconfigure::Server(getPrivateNodeHandle())); + get_options_service_ = nh_.advertiseService(SETTINGS_SERVICE, &RealsenseNodelet::getCameraOptionValues, this); bool connected = false; @@ -119,8 +100,8 @@ namespace realsense_camera if (connected == true) { // Start working thread. - device_thread_ = - boost::shared_ptr (new boost::thread (boost::bind(&RealsenseNodelet::devicePoll, this))); + stream_thread_ = + boost::shared_ptr (new boost::thread (boost::bind(&RealsenseNodelet::publishStreams, this))); if (enable_tf_ == true) { @@ -134,12 +115,10 @@ namespace realsense_camera ROS_ERROR_STREAM(nodelet_name_ << " - Couldn't connect to camera! Shutting down..."); ros::shutdown(); } - - dynamic_reconf_server_->setCallback(boost::bind(&RealsenseNodelet::configCallback, this, _1, _2)); } /* - *Private Methods. + *Protected Methods. */ void RealsenseNodelet::enableColorStream() { @@ -185,6 +164,8 @@ namespace realsense_camera { prepareStreamCalibData (RS_STREAM_DEPTH); } + // must enable IR stream also + enableInfraredStream(); } void RealsenseNodelet::enableInfraredStream() @@ -210,99 +191,22 @@ namespace realsense_camera } } - void RealsenseNodelet::enableInfrared2Stream() + void RealsenseNodelet::disableDepthStream() { - // Enable streams. - if (mode_.compare ("manual") == 0) - { - ROS_INFO_STREAM(nodelet_name_ << " - Enabling Infrared2 stream: manual mode"); - rs_enable_stream(rs_device_, RS_STREAM_INFRARED2, depth_width_, depth_height_, IR2_FORMAT, depth_fps_, 0); - } - else - { - ROS_INFO_STREAM(nodelet_name_ << " - Enabling Infrared2 stream: preset mode"); - rs_enable_stream_preset(rs_device_, RS_STREAM_INFRARED2, RS_PRESET_BEST_QUALITY, 0); - } + // disable depth stream + ROS_INFO_STREAM(nodelet_name_ << " - Disabling Depth stream"); + rs_disable_stream(rs_device_, RS_STREAM_DEPTH, &rs_error_); + checkError(); - uint32_t stream_index = (uint32_t) RS_STREAM_INFRARED2; - if (camera_info_[stream_index] == NULL) - { - prepareStreamCalibData (RS_STREAM_INFRARED2); - } + // disable IR stream + disableInfraredStream(); } - - - void RealsenseNodelet::configCallback(realsense_camera::camera_paramsConfig &config, uint32_t level) + void RealsenseNodelet::disableInfraredStream() { - rs_set_device_option(rs_device_, RS_OPTION_COLOR_BACKLIGHT_COMPENSATION, config.color_backlight_compensation, 0); - rs_set_device_option(rs_device_, RS_OPTION_COLOR_BRIGHTNESS, config.color_brightness, 0); - rs_set_device_option(rs_device_, RS_OPTION_COLOR_CONTRAST, config.color_contrast, 0); - rs_set_device_option(rs_device_, RS_OPTION_COLOR_GAIN, config.color_gain, 0); - rs_set_device_option(rs_device_, RS_OPTION_COLOR_GAMMA, config.color_gamma, 0); - rs_set_device_option(rs_device_, RS_OPTION_COLOR_HUE, config.color_hue, 0); - rs_set_device_option(rs_device_, RS_OPTION_COLOR_SATURATION, config.color_saturation, 0); - rs_set_device_option(rs_device_, RS_OPTION_COLOR_SHARPNESS, config.color_sharpness, 0); - rs_set_device_option(rs_device_, RS_OPTION_COLOR_ENABLE_AUTO_WHITE_BALANCE, config.color_enable_auto_white_balance, 0); - - if (config.color_enable_auto_white_balance == 0) - { - rs_set_device_option(rs_device_, RS_OPTION_COLOR_WHITE_BALANCE, config.color_white_balance, 0); - } - - //R200 camera specific options - rs_set_device_option(rs_device_, RS_OPTION_R200_LR_AUTO_EXPOSURE_ENABLED, config.r200_lr_auto_exposure_enabled, 0); - - if (config.r200_lr_auto_exposure_enabled == 0) - { - rs_set_device_option(rs_device_, RS_OPTION_R200_LR_EXPOSURE, config.r200_lr_exposure, 0); - } - - rs_set_device_option(rs_device_, RS_OPTION_R200_LR_GAIN, config.r200_lr_gain, 0); - rs_set_device_option(rs_device_, RS_OPTION_R200_EMITTER_ENABLED, config.r200_emitter_enabled, 0); - - if (config.r200_lr_auto_exposure_enabled == 1) - { - if (config.r200_auto_exposure_top_edge >= depth_height_) - { - config.r200_auto_exposure_top_edge = depth_height_ - 1; - } - if (config.r200_auto_exposure_bottom_edge >= depth_height_) - { - config.r200_auto_exposure_bottom_edge = depth_height_ - 1; - } - if (config.r200_auto_exposure_left_edge >= depth_width_) - { - config.r200_auto_exposure_left_edge = depth_width_ - 1; - } - if (config.r200_auto_exposure_right_edge >= depth_width_) - { - config.r200_auto_exposure_right_edge = depth_width_ - 1; - } - edge_values_[0] = config.r200_auto_exposure_left_edge; - edge_values_[1] = config.r200_auto_exposure_top_edge; - edge_values_[2] = config.r200_auto_exposure_right_edge; - edge_values_[3] = config.r200_auto_exposure_bottom_edge; - - rs_set_device_options(rs_device_, edge_options_, 4, edge_values_, 0); - } - - if (config.enable_depth == false) - { - if (enable_color_ == false) - { - ROS_INFO_STREAM(nodelet_name_ << " - Color stream is also disabled. Cannot disable depth stream"); - config.enable_depth = true; - } - else - { - enable_depth_ = false; - } - } - else - { - enable_depth_ = true; - } + ROS_INFO_STREAM(nodelet_name_ << " - Disabling Infrared stream"); + rs_disable_stream(rs_device_, RS_STREAM_INFRARED, &rs_error_); + checkError(); } void RealsenseNodelet::checkError() @@ -319,16 +223,18 @@ namespace realsense_camera } } - /* - * Query the data for every frame and publish it to the different topics. - */ - void RealsenseNodelet::devicePoll() +void RealsenseNodelet::enableStreams() +{ + // Enable streams. + if (enable_color_ == true) { - while (ros::ok()) - { - publishStreams(); - } + enableColorStream(); } + if (enable_depth_ == true) + { + enableDepthStream(); + } +} bool RealsenseNodelet::connectToCamera() { @@ -395,18 +301,7 @@ namespace realsense_camera checkError(); // Enable streams. - if (enable_color_ == true) - { - enableColorStream(); - } - - if (enable_depth_ == true) - { - enableDepthStream(); - enableInfraredStream(); - enableInfrared2Stream(); - } - + enableStreams(); getCameraOptions(); setStaticCameraOptions(); @@ -468,16 +363,12 @@ namespace realsense_camera */ void RealsenseNodelet::allocateResources() { - // Prepare camera for enabled streams (color/depth/infrared/infrared2). + // Prepare camera for enabled streams (color/depth/infrared) fillStreamEncoding(); image_[(uint32_t) RS_STREAM_COLOR] = cv::Mat(color_height_, color_width_, CV_8UC3, cv::Scalar (0, 0, 0)); image_[(uint32_t) RS_STREAM_DEPTH] = cv::Mat(depth_height_, depth_width_, CV_16UC1, cv::Scalar (0)); image_[(uint32_t) RS_STREAM_INFRARED] = cv::Mat(depth_height_, depth_width_, CV_8UC1, cv::Scalar (0)); - if (camera_.find(R200) != std::string::npos) - { - image_[(uint32_t) RS_STREAM_INFRARED2] = cv::Mat(depth_height_, depth_width_, CV_8UC1, cv::Scalar (0)); - } } /* @@ -577,7 +468,7 @@ namespace realsense_camera { pnh_.getParam("serial_no", serial_no_); pnh_.getParam("usb_port_id", usb_port_id_); - pnh_.param("camera", camera_, (std::string) R200); + pnh_.getParam("camera", camera_); pnh_.param("mode", mode_, DEFAULT_MODE); pnh_.param("enable_depth", enable_depth_, ENABLE_DEPTH); pnh_.param("enable_color", enable_color_, ENABLE_COLOR); @@ -595,93 +486,21 @@ namespace realsense_camera pnh_.param("depth_optical_frame_id", depth_optical_frame_id_, DEFAULT_DEPTH_OPTICAL_FRAME_ID); pnh_.param("color_optical_frame_id", color_optical_frame_id_, DEFAULT_COLOR_OPTICAL_FRAME_ID); pnh_.param("ir_frame_id", ir_frame_id_, DEFAULT_IR_FRAME_ID); - pnh_.param("ir2_frame_id", ir2_frame_id_, DEFAULT_IR2_FRAME_ID); } - /* - * Set the static camera options. - */ - void RealsenseNodelet::setStaticCameraOptions() - { - // Get dynamic options from the dynamic reconfigure server. - camera_paramsConfig params_config; - dynamic_reconf_server_->getConfigDefault(params_config); - std::vector param_desc = params_config.__getParamDescriptions__(); - - // Iterate through the supported camera options - for (CameraOptions o: camera_options_) - { - std::string opt_name = rs_option_to_string(o.opt); - bool found = false; - - std::vector::iterator it; - for (camera_paramsConfig::AbstractParamDescriptionConstPtr param_desc_ptr: param_desc) - { - std::transform(opt_name.begin(), opt_name.end(), opt_name.begin(), ::tolower); - if (opt_name.compare((* param_desc_ptr).name) == 0) - { - found = true; - break; - } - } - // Skip the dynamic options and set only the static camera options. - if (found == false) - { - std::string key; - double val; - - if (pnh_.searchParam(opt_name, key)) - { - double opt_val; - pnh_.getParam(key, val); - - // Validate and set the input values within the min-max range - if (val < o.min) - { - opt_val = o.min; - } - else if (val > o.max) - { - opt_val = o.max; - } - else - { - opt_val = val; - } - ROS_INFO_STREAM(nodelet_name_ << " - Static Options: " << opt_name << " = " << opt_val); - rs_set_device_option(rs_device_, o.opt, opt_val, &rs_error_); - checkError(); - } - } - } - } /* * Copy frame data from realsense to member cv images. */ void RealsenseNodelet::prepareStreamData(rs_stream rs_strm) { - switch (rs_strm) + if (rs_strm == RS_STREAM_DEPTH) { - case RS_STREAM_COLOR: - image_[(uint32_t) RS_STREAM_COLOR].data = (unsigned char *) (rs_get_frame_data(rs_device_, RS_STREAM_COLOR, 0)); - break; - case RS_STREAM_DEPTH: + // fill depth buffer image_depth16_ = reinterpret_cast (rs_get_frame_data(rs_device_, RS_STREAM_DEPTH, 0)); - image_[(uint32_t) RS_STREAM_DEPTH].data = (unsigned char *) image_depth16_; - break; - case RS_STREAM_INFRARED: - image_[(uint32_t) RS_STREAM_INFRARED].data = - (unsigned char *) (rs_get_frame_data(rs_device_, RS_STREAM_INFRARED, 0)); - break; - case RS_STREAM_INFRARED2: - image_[(uint32_t) RS_STREAM_INFRARED2].data = - (unsigned char *) (rs_get_frame_data(rs_device_, RS_STREAM_INFRARED2, 0)); - break; - default: - // no other streams supported - break; } + // fill image buffer for stream + image_[(uint32_t) rs_strm].data = (unsigned char *) (rs_get_frame_data(rs_device_, rs_strm, 0)); } /* @@ -695,8 +514,6 @@ namespace realsense_camera stream_step_[(uint32_t) RS_STREAM_DEPTH] = depth_width_ * sizeof (uint16_t); stream_encoding_[(uint32_t) RS_STREAM_INFRARED] = sensor_msgs::image_encodings::TYPE_8UC1; stream_step_[(uint32_t) RS_STREAM_INFRARED] = depth_width_ * sizeof (unsigned char); - stream_encoding_[(uint32_t) RS_STREAM_INFRARED2] = sensor_msgs::image_encodings::TYPE_8UC1; - stream_step_[(uint32_t) RS_STREAM_INFRARED2] = depth_width_ * sizeof (unsigned char); } /* @@ -704,114 +521,104 @@ namespace realsense_camera */ void RealsenseNodelet::publishStreams() { - if (enable_depth_ == false && rs_is_stream_enabled(rs_device_, RS_STREAM_DEPTH, 0) == 1) + while (ros::ok()) { - if (rs_is_device_streaming(rs_device_, 0) == 1) + if (enable_depth_ == false && rs_is_stream_enabled(rs_device_, RS_STREAM_DEPTH, 0) == 1) { - ROS_INFO_STREAM(nodelet_name_ << " - Stopping camera"); - rs_stop_device(rs_device_, &rs_error_); - checkError(); - } + if (rs_is_device_streaming(rs_device_, 0) == 1) + { + ROS_INFO_STREAM(nodelet_name_ << " - Stopping camera"); + rs_stop_device(rs_device_, &rs_error_); + checkError(); + } + // disable depth stream + disableDepthStream(); - //disable depth, infrared1 and infrared2 streams - ROS_INFO_STREAM(nodelet_name_ << " - Disabling Depth stream"); - rs_disable_stream(rs_device_, RS_STREAM_DEPTH, &rs_error_); - checkError(); + if (rs_is_device_streaming(rs_device_, 0) == 0) + { + ROS_INFO_STREAM(nodelet_name_ << " - Starting camera"); + rs_start_device(rs_device_, &rs_error_); + checkError(); + } + } - ROS_INFO_STREAM(nodelet_name_ << " - Disabling Infrared stream"); - rs_disable_stream(rs_device_, RS_STREAM_INFRARED, &rs_error_); - checkError(); + if (enable_depth_ == true && rs_is_stream_enabled(rs_device_, RS_STREAM_DEPTH, 0) == 0) + { + if (rs_is_device_streaming(rs_device_, 0) == 1) + { + ROS_INFO_STREAM(nodelet_name_ << " - Stopping camera"); + rs_stop_device(rs_device_, &rs_error_); + checkError(); + } - ROS_INFO_STREAM(nodelet_name_ << " - Disabling Infrared2 stream"); - rs_disable_stream(rs_device_, RS_STREAM_INFRARED2, &rs_error_); - checkError(); + enableDepthStream(); - if (rs_is_device_streaming(rs_device_, 0) == 0) - { - ROS_INFO_STREAM(nodelet_name_ << " - Starting camera"); - rs_start_device(rs_device_, &rs_error_); - checkError(); + if (rs_is_device_streaming(rs_device_, 0) == 0) + { + ROS_INFO_STREAM(nodelet_name_ << " - Starting camera"); + rs_start_device(rs_device_, &rs_error_); + checkError(); + } } - } - if (enable_depth_ == true && rs_is_stream_enabled(rs_device_, RS_STREAM_DEPTH, 0) == 0) - { if (rs_is_device_streaming(rs_device_, 0) == 1) { - ROS_INFO_STREAM(nodelet_name_ << " - Stopping camera"); - rs_stop_device(rs_device_, &rs_error_); + rs_wait_for_frames(rs_device_, &rs_error_); checkError(); - } - - enableDepthStream(); - enableInfraredStream(); - enableInfrared2Stream(); - - if (rs_is_device_streaming(rs_device_, 0) == 0) - { - ROS_INFO_STREAM(nodelet_name_ << " - Starting camera"); - rs_start_device(rs_device_, &rs_error_); - checkError(); - } - } + time_stamp_ = ros::Time::now(); + bool duplicate_depth_color = false; - if (rs_is_device_streaming(rs_device_, 0) == 1) - { - rs_wait_for_frames(rs_device_, &rs_error_); - checkError(); - time_stamp_ = ros::Time::now(); - bool duplicate_depth_color = false; - - for (int stream_index = 0; stream_index < STREAM_COUNT; ++stream_index) - { - // Publish image stream only if there is at least one subscriber. - if (camera_publisher_[stream_index].getNumSubscribers() > 0 && - rs_is_stream_enabled(rs_device_, (rs_stream) stream_index, 0) == 1) + for (int stream_index = 0; stream_index < num_streams_; ++stream_index) { - int current_ts = rs_get_frame_timestamp(rs_device_, (rs_stream) stream_index, 0); - if (stream_ts_[stream_index] != current_ts) // Publish frames only if its not duplicate + // Publish image stream only if there is at least one subscriber. + if (camera_publisher_[stream_index].getNumSubscribers() > 0 && + rs_is_stream_enabled(rs_device_, (rs_stream) stream_index, 0) == 1) { - prepareStreamData((rs_stream) stream_index); + int current_ts = rs_get_frame_timestamp(rs_device_, (rs_stream) stream_index, 0); + if (stream_ts_[stream_index] != current_ts) // Publish frames only if its not duplicate + { + prepareStreamData((rs_stream) stream_index); - sensor_msgs::ImagePtr msg = cv_bridge::CvImage(std_msgs::Header(), - stream_encoding_[stream_index], - image_[stream_index]).toImageMsg(); + sensor_msgs::ImagePtr msg = cv_bridge::CvImage(std_msgs::Header(), + stream_encoding_[stream_index], + image_[stream_index]).toImageMsg(); - msg->header.frame_id = frame_id_[stream_index]; - msg->header.stamp = time_stamp_; // Publish timestamp to synchronize frames. - msg->width = image_[stream_index].cols; - msg->height = image_[stream_index].rows; - msg->is_bigendian = false; - msg->step = stream_step_[stream_index]; + msg->header.frame_id = frame_id_[stream_index]; + msg->header.stamp = time_stamp_; // Publish timestamp to synchronize frames. + msg->width = image_[stream_index].cols; + msg->height = image_[stream_index].rows; + msg->is_bigendian = false; + msg->step = stream_step_[stream_index]; - camera_info_ptr_[stream_index]->header.stamp = msg->header.stamp; - camera_publisher_[stream_index].publish (msg, camera_info_ptr_[stream_index]); - } - else - { - if ((stream_index == RS_STREAM_DEPTH) || (stream_index == RS_STREAM_COLOR)) + camera_info_ptr_[stream_index]->header.stamp = msg->header.stamp; + camera_publisher_[stream_index].publish (msg, camera_info_ptr_[stream_index]); + } + else { - duplicate_depth_color = true; // Set this flag to true if Depth and/or Color frame is duplicate + if ((stream_index == RS_STREAM_DEPTH) || (stream_index == RS_STREAM_COLOR)) + { + duplicate_depth_color = true; // Set this flag to true if Depth and/or Color frame is duplicate + } } + stream_ts_[stream_index] = current_ts; } - stream_ts_[stream_index] = current_ts; } - } - if (pointcloud_publisher_.getNumSubscribers() > 0 && - rs_is_stream_enabled(rs_device_, RS_STREAM_DEPTH, 0) == 1 && enable_pointcloud_ == true && - (duplicate_depth_color == false)) // Skip publishing PointCloud if Depth and/or Color frame was duplicate - { - if (camera_publisher_[(uint32_t) RS_STREAM_DEPTH].getNumSubscribers() <= 0) - { - prepareStreamData(RS_STREAM_DEPTH); - } - if (camera_publisher_[(uint32_t) RS_STREAM_COLOR].getNumSubscribers() <= 0) + if (pointcloud_publisher_.getNumSubscribers() > 0 && + rs_is_stream_enabled(rs_device_, RS_STREAM_DEPTH, 0) == 1 && enable_pointcloud_ == true && + (duplicate_depth_color == false)) // Skip publishing PointCloud if Depth and/or Color frame was duplicate { - prepareStreamData(RS_STREAM_COLOR); + if (camera_publisher_[(uint32_t) RS_STREAM_DEPTH].getNumSubscribers() <= 0) + { + prepareStreamData(RS_STREAM_DEPTH); + } + if (camera_publisher_[(uint32_t) RS_STREAM_COLOR].getNumSubscribers() <= 0) + { + prepareStreamData(RS_STREAM_COLOR); + } + publishPointCloud(image_[(uint32_t) RS_STREAM_COLOR]); } - publishPointCloud(image_[(uint32_t) RS_STREAM_COLOR]); } } } diff --git a/realsense_camera/src/realsense_camera_nodelet.h b/realsense_camera/src/realsense_camera_nodelet.h index c2866e3bae..bab69a30de 100644 --- a/realsense_camera/src/realsense_camera_nodelet.h +++ b/realsense_camera/src/realsense_camera_nodelet.h @@ -60,146 +60,141 @@ #include #include -#include -#include - +#include +#include namespace realsense_camera { -class RealsenseNodelet: public nodelet::Nodelet -{ -public: - - // Interfaces. - virtual void onInit(); - virtual ~ RealsenseNodelet(); - - // Default Constants. - const int MAX_Z = 8; // in meters - const std::string DEFAULT_MODE = "preset"; - const int DEPTH_HEIGHT = 360; - const int DEPTH_WIDTH = 480; - const int COLOR_HEIGHT = 480; - const int COLOR_WIDTH = 640; - const int DEPTH_FPS = 60; - const int COLOR_FPS = 60; - const bool ENABLE_DEPTH = true; - const bool ENABLE_COLOR = true; - const bool ENABLE_PC = true; - const bool ENABLE_TF = true; - const rs_format DEPTH_FORMAT = RS_FORMAT_Z16; - const rs_format COLOR_FORMAT = RS_FORMAT_RGB8; - const rs_format IR1_FORMAT = RS_FORMAT_Y8; - const rs_format IR2_FORMAT = RS_FORMAT_Y8; - const std::string DEFAULT_BASE_FRAME_ID = "camera_link"; - const std::string DEFAULT_DEPTH_FRAME_ID = "camera_depth_frame"; - const std::string DEFAULT_COLOR_FRAME_ID = "camera_rgb_frame"; - const std::string DEFAULT_DEPTH_OPTICAL_FRAME_ID = "camera_depth_optical_frame"; - const std::string DEFAULT_COLOR_OPTICAL_FRAME_ID = "camera_rgb_optical_frame"; - const std::string DEFAULT_IR_FRAME_ID = "camera_infrared_frame"; - const std::string DEFAULT_IR2_FRAME_ID = "camera_infrared2_frame"; - const char *DEPTH_TOPIC = "camera/depth/image_raw"; - const char *COLOR_TOPIC = "camera/color/image_raw"; - const char *IR1_TOPIC = "camera/infrared1/image_raw"; - const char *IR2_TOPIC = "camera/infrared2/image_raw"; - const char *PC_TOPIC = "camera/depth/points"; - const char *SETTINGS_SERVICE = "camera/get_settings"; - const char *R200 = "R200"; - const static int STREAM_COUNT = 4; - -private: - // Member Variables. - boost::shared_ptr device_thread_; - boost::shared_ptr transform_thread_; - - rs_error *rs_error_ = 0; - rs_context *rs_context_; - rs_device *rs_device_; - std::vector rs_detected_devices_; - - int num_of_cameras_; - std::string serial_no_; - std::string usb_port_id_; - int color_height_; - int color_width_; - int depth_height_; - int depth_width_; - int depth_fps_; - int color_fps_; - bool is_device_started_; - bool enable_color_; - bool enable_depth_; - bool enable_pointcloud_; - bool enable_tf_; - std::string base_frame_id_; - std::string depth_frame_id_; - std::string color_frame_id_; - std::string depth_optical_frame_id_; - std::string color_optical_frame_id_; - std::string ir_frame_id_; - std::string ir2_frame_id_; - std::string camera_ = "R200"; - std::string nodelet_name_; - const uint16_t *image_depth16_; - - cv::Mat image_[STREAM_COUNT]; - - rs_option edge_options_[4] = { - RS_OPTION_R200_AUTO_EXPOSURE_LEFT_EDGE, - RS_OPTION_R200_AUTO_EXPOSURE_TOP_EDGE, - RS_OPTION_R200_AUTO_EXPOSURE_RIGHT_EDGE, - RS_OPTION_R200_AUTO_EXPOSURE_BOTTOM_EDGE - }; - double edge_values_[4]; - - sensor_msgs::CameraInfoPtr camera_info_ptr_[STREAM_COUNT]; - sensor_msgs::CameraInfo * camera_info_[STREAM_COUNT]; - image_transport::CameraPublisher camera_publisher_[STREAM_COUNT]; - - ros::Time time_stamp_; - ros::Publisher pointcloud_publisher_; - ros::ServiceServer get_options_service_; - ros::NodeHandle pnh_; - - std::string frame_id_[STREAM_COUNT]; - std::string stream_encoding_[STREAM_COUNT]; - std::string mode_; - std::map config_; - int stream_step_[STREAM_COUNT]; - int stream_ts_[STREAM_COUNT]; - - struct CameraOptions + class RealsenseNodelet: public nodelet::Nodelet { - rs_option opt; - double min, max, step, value; + public: + + // Interfaces. + virtual void onInit(); + virtual ~RealsenseNodelet(); + virtual void publishTransforms(); + virtual void publishStreams(); + virtual bool getCameraOptionValues(realsense_camera::cameraConfiguration::Request & req, realsense_camera::cameraConfiguration::Response & res); + + protected: + // Default Constants. + const int MAX_Z = 8; // in meters + const std::string DEFAULT_MODE = "preset"; + const int DEPTH_HEIGHT = 360; + const int DEPTH_WIDTH = 480; + const int COLOR_HEIGHT = 480; + const int COLOR_WIDTH = 640; + const int DEPTH_FPS = 60; + const int COLOR_FPS = 60; + const bool ENABLE_DEPTH = true; + const bool ENABLE_COLOR = true; + const bool ENABLE_PC = true; + const bool ENABLE_TF = true; + const rs_format DEPTH_FORMAT = RS_FORMAT_Z16; + const rs_format COLOR_FORMAT = RS_FORMAT_RGB8; + const rs_format IR1_FORMAT = RS_FORMAT_Y8; + const std::string DEFAULT_BASE_FRAME_ID = "camera_link"; + const std::string DEFAULT_DEPTH_FRAME_ID = "camera_depth_frame"; + const std::string DEFAULT_COLOR_FRAME_ID = "camera_rgb_frame"; + const std::string DEFAULT_DEPTH_OPTICAL_FRAME_ID = "camera_depth_optical_frame"; + const std::string DEFAULT_COLOR_OPTICAL_FRAME_ID = "camera_rgb_optical_frame"; + const std::string DEFAULT_IR_FRAME_ID = "camera_infrared_frame"; + const char *DEPTH_TOPIC = "camera/depth/image_raw"; + const char *COLOR_TOPIC = "camera/color/image_raw"; + const char *IR1_TOPIC = "camera/infrared1/image_raw"; + const char *PC_TOPIC = "camera/depth/points"; + const char *SETTINGS_SERVICE = "camera/get_settings"; + + const static int STREAM_COUNT = 4; + + // Member Variables. + boost::shared_ptr stream_thread_; + boost::shared_ptr transform_thread_; + + rs_error *rs_error_ = 0; + rs_context *rs_context_; + rs_device *rs_device_; + std::vector rs_detected_devices_; + + int num_of_cameras_; + std::string serial_no_; + std::string usb_port_id_; + int color_height_; + int color_width_; + int depth_height_; + int depth_width_; + int depth_fps_; + int color_fps_; + bool is_device_started_; + bool enable_color_; + bool enable_depth_; + bool enable_pointcloud_; + bool enable_tf_; + std::string base_frame_id_; + std::string depth_frame_id_; + std::string color_frame_id_; + std::string depth_optical_frame_id_; + std::string color_optical_frame_id_; + std::string ir_frame_id_; + std::string camera_; + std::string nodelet_name_; + const uint16_t *image_depth16_; + int num_streams_ = 3; + + cv::Mat image_[STREAM_COUNT]; + + rs_option edge_options_[4] = { + RS_OPTION_R200_AUTO_EXPOSURE_LEFT_EDGE, + RS_OPTION_R200_AUTO_EXPOSURE_TOP_EDGE, + RS_OPTION_R200_AUTO_EXPOSURE_RIGHT_EDGE, + RS_OPTION_R200_AUTO_EXPOSURE_BOTTOM_EDGE + }; + double edge_values_[4]; + + sensor_msgs::CameraInfoPtr camera_info_ptr_[STREAM_COUNT]; + sensor_msgs::CameraInfo * camera_info_[STREAM_COUNT]; + image_transport::CameraPublisher camera_publisher_[STREAM_COUNT]; + + ros::Time time_stamp_; + ros::Publisher pointcloud_publisher_; + ros::ServiceServer get_options_service_; + ros::NodeHandle nh_; + ros::NodeHandle pnh_; + + std::string frame_id_[STREAM_COUNT]; + std::string stream_encoding_[STREAM_COUNT]; + std::string mode_; + std::map config_; + int stream_step_[STREAM_COUNT]; + int stream_ts_[STREAM_COUNT]; + + struct CameraOptions + { + rs_option opt; + double min, max, step, value; + }; + std::vector camera_options_; + + // Member Functions. + virtual void enableStreams(); + virtual void enableColorStream(); + virtual void enableDepthStream(); + virtual void disableDepthStream(); + virtual void enableInfraredStream(); + virtual void disableInfraredStream(); + virtual void fillStreamEncoding(); + virtual void setStreamOptions(); + virtual void prepareStreamCalibData(rs_stream calib_data); + virtual void prepareStreamData(rs_stream rs_strm); + + virtual void getCameraOptions(); + virtual void allocateResources(); + virtual void listCameras(); + virtual bool connectToCamera(); + virtual void setStaticCameraOptions() { return; } // must be defined in derived class + virtual void checkError(); + + virtual void publishPointCloud(cv::Mat & image_rgb); }; - std::vector camera_options_; - boost::shared_ptr> dynamic_reconf_server_; - - // Member Functions. - void enableColorStream(); - void enableDepthStream(); - void enableInfraredStream(); - void enableInfrared2Stream(); - void checkError(); - void fetchCalibData(); - void prepareStreamCalibData(rs_stream calib_data); - void prepareStreamData(rs_stream rs_strm); - void publishStreams(); - void publishPointCloud(cv::Mat & image_rgb); - void publishTransforms(); - void devicePoll(); - void getCameraOptions(); - void allocateResources(); - bool connectToCamera(); - void fillStreamEncoding(); - void setStreamOptions(); - void setStaticCameraOptions(); - bool getCameraOptionValues(realsense_camera::cameraConfiguration::Request & req, realsense_camera::cameraConfiguration::Response & res); - void configCallback(realsense_camera::camera_paramsConfig &config, uint32_t level); - void listCameras(); - -}; } - #endif diff --git a/realsense_camera/src/realsense_camera_nodelet_r200.cpp b/realsense_camera/src/realsense_camera_nodelet_r200.cpp new file mode 100644 index 0000000000..1a402e5c55 --- /dev/null +++ b/realsense_camera/src/realsense_camera_nodelet_r200.cpp @@ -0,0 +1,285 @@ +/****************************************************************************** + Copyright (c) 2016, Intel Corporation + All rights reserved. + + Redistribution and use in source and binary forms, with or without + modification, are permitted provided that the following conditions are met: + + 1. Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + + 2. Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + + 3. Neither the name of the copyright holder nor the names of its contributors + may be used to endorse or promote products derived from this software without + specific prior written permission. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + *******************************************************************************/ + +#include "realsense_camera_nodelet_r200.h" + +PLUGINLIB_EXPORT_CLASS (realsense_camera::RealsenseNodeletR200, nodelet::Nodelet) + +namespace realsense_camera +{ + /* + * Public Methods. + */ + + /* + * Initialize the realsense camera + */ + void RealsenseNodeletR200::onInit() + { + // set member vars used in base class + nodelet_name_ = getName(); + num_streams_ = NUM_STREAMS_R200; + nh_ = getNodeHandle(); + pnh_ = getPrivateNodeHandle(); + + // create dynamic reconfigure server - this must be done before calling base class onInit() + // onInit() calls setStaticCameraOptions() which relies on this being set already + dynamic_reconf_server_.reset(new dynamic_reconfigure::Server(pnh_)); + + // call base class onInit() method + RealsenseNodelet::onInit(); + + // Set up the IR2 frame and topics + frame_id_[RS_STREAM_INFRARED2] = ir2_frame_id_; + image_transport::ImageTransport it (nh_); + camera_publisher_[RS_STREAM_INFRARED2] = it.advertiseCamera(IR2_TOPIC, 1); + + // setCallback can only be called after rs_device_ is set by base class connectToCamera() + dynamic_reconf_server_->setCallback(boost::bind(&RealsenseNodeletR200::configCallback, this, _1, _2)); + } + + /* + *Protected Methods. + */ + void RealsenseNodeletR200::enableDepthStream() + { + // call the base class method first + RealsenseNodelet::enableDepthStream(); + // enable IR2 stream + enableInfrared2Stream(); + } + + void RealsenseNodeletR200::disableDepthStream() + { + // call the base class method first + RealsenseNodelet::disableDepthStream(); + // disable IR2 stream + disableInfrared2Stream(); + } + + void RealsenseNodeletR200::enableInfrared2Stream() + { + // Enable streams. + if (mode_.compare ("manual") == 0) + { + ROS_INFO_STREAM(nodelet_name_ << " - Enabling Infrared2 stream: manual mode"); + rs_enable_stream(rs_device_, RS_STREAM_INFRARED2, depth_width_, depth_height_, IR2_FORMAT, depth_fps_, &rs_error_); + checkError(); + } + else + { + ROS_INFO_STREAM(nodelet_name_ << " - Enabling Infrared2 stream: preset mode"); + rs_enable_stream_preset(rs_device_, RS_STREAM_INFRARED2, RS_PRESET_BEST_QUALITY, &rs_error_); + checkError(); + } + + uint32_t stream_index = (uint32_t) RS_STREAM_INFRARED2; + if (camera_info_[stream_index] == NULL) + { + prepareStreamCalibData (RS_STREAM_INFRARED2); + } + } + + void RealsenseNodeletR200::disableInfrared2Stream() + { + ROS_INFO_STREAM(nodelet_name_ << " - Disabling Infrared2 stream"); + rs_disable_stream(rs_device_, RS_STREAM_INFRARED2, &rs_error_); + checkError(); + } + + void RealsenseNodeletR200::configCallback(realsense_camera::camera_params_r200Config &config, uint32_t level) + { + // Set common options + rs_set_device_option(rs_device_, RS_OPTION_COLOR_BACKLIGHT_COMPENSATION, config.color_backlight_compensation, 0); + rs_set_device_option(rs_device_, RS_OPTION_COLOR_BRIGHTNESS, config.color_brightness, 0); + rs_set_device_option(rs_device_, RS_OPTION_COLOR_CONTRAST, config.color_contrast, 0); + rs_set_device_option(rs_device_, RS_OPTION_COLOR_GAIN, config.color_gain, 0); + rs_set_device_option(rs_device_, RS_OPTION_COLOR_GAMMA, config.color_gamma, 0); + rs_set_device_option(rs_device_, RS_OPTION_COLOR_HUE, config.color_hue, 0); + rs_set_device_option(rs_device_, RS_OPTION_COLOR_SATURATION, config.color_saturation, 0); + rs_set_device_option(rs_device_, RS_OPTION_COLOR_SHARPNESS, config.color_sharpness, 0); + rs_set_device_option(rs_device_, RS_OPTION_COLOR_ENABLE_AUTO_WHITE_BALANCE, config.color_enable_auto_white_balance, 0); + + if (config.color_enable_auto_white_balance == 0) + { + rs_set_device_option(rs_device_, RS_OPTION_COLOR_WHITE_BALANCE, config.color_white_balance, 0); + } + + if (config.enable_depth == false) + { + if (enable_color_ == false) + { + ROS_INFO_STREAM(nodelet_name_ << " - Color stream is also disabled. Cannot disable depth stream"); + config.enable_depth = true; + } + else + { + enable_depth_ = false; + } + } + else + { + enable_depth_ = true; + } + + //R200 camera specific options + rs_set_device_option(rs_device_, RS_OPTION_R200_LR_AUTO_EXPOSURE_ENABLED, config.r200_lr_auto_exposure_enabled, 0); + + if (config.r200_lr_auto_exposure_enabled == 0) + { + rs_set_device_option(rs_device_, RS_OPTION_R200_LR_EXPOSURE, config.r200_lr_exposure, 0); + } + + rs_set_device_option(rs_device_, RS_OPTION_R200_LR_GAIN, config.r200_lr_gain, 0); + rs_set_device_option(rs_device_, RS_OPTION_R200_EMITTER_ENABLED, config.r200_emitter_enabled, 0); + + if (config.r200_lr_auto_exposure_enabled == 1) + { + if (config.r200_auto_exposure_top_edge >= depth_height_) + { + config.r200_auto_exposure_top_edge = depth_height_ - 1; + } + if (config.r200_auto_exposure_bottom_edge >= depth_height_) + { + config.r200_auto_exposure_bottom_edge = depth_height_ - 1; + } + if (config.r200_auto_exposure_left_edge >= depth_width_) + { + config.r200_auto_exposure_left_edge = depth_width_ - 1; + } + if (config.r200_auto_exposure_right_edge >= depth_width_) + { + config.r200_auto_exposure_right_edge = depth_width_ - 1; + } + edge_values_[0] = config.r200_auto_exposure_left_edge; + edge_values_[1] = config.r200_auto_exposure_top_edge; + edge_values_[2] = config.r200_auto_exposure_right_edge; + edge_values_[3] = config.r200_auto_exposure_bottom_edge; + + rs_set_device_options(rs_device_, edge_options_, 4, edge_values_, 0); + } + } + + /* + * Define buffer for images and prepare camera info for each enabled stream. + */ + void RealsenseNodeletR200::allocateResources() + { + // call base class method first + RealsenseNodelet::allocateResources(); + // set IR2 image buffer + image_[(uint32_t) RS_STREAM_INFRARED2] = cv::Mat(depth_height_, depth_width_, CV_8UC1, cv::Scalar (0)); + } + + /* + * Set the stream options based on input params. + */ + void RealsenseNodeletR200::setStreamOptions() + { + // call base class method first + RealsenseNodelet::setStreamOptions(); + // setup R200 specific frame + pnh_.param("ir2_frame_id", ir2_frame_id_, DEFAULT_IR2_FRAME_ID); + } + + /* + * Populate the encodings for each stream. + */ + void RealsenseNodeletR200::fillStreamEncoding() + { + // Call base class method first + RealsenseNodelet::fillStreamEncoding(); + // Setup IR2 stream + stream_encoding_[(uint32_t) RS_STREAM_INFRARED2] = sensor_msgs::image_encodings::TYPE_8UC1; + stream_step_[(uint32_t) RS_STREAM_INFRARED2] = depth_width_ * sizeof (unsigned char); + } + + /* + * Set the static camera options. + */ + void RealsenseNodeletR200::setStaticCameraOptions() + { + ROS_INFO_STREAM(nodelet_name_ << " - Setting camera options"); + + // Get dynamic options from the dynamic reconfigure server. + realsense_camera::camera_params_r200Config params_config; + dynamic_reconf_server_->getConfigDefault(params_config); + + std::vector param_desc = params_config.__getParamDescriptions__(); + + // Iterate through the supported camera options + for (CameraOptions o: camera_options_) + { + std::string opt_name = rs_option_to_string(o.opt); + bool found = false; + + std::vector::iterator it; + for (realsense_camera::camera_params_r200Config::AbstractParamDescriptionConstPtr param_desc_ptr: param_desc) + { + std::transform(opt_name.begin(), opt_name.end(), opt_name.begin(), ::tolower); + if (opt_name.compare((* param_desc_ptr).name) == 0) + { + found = true; + break; + } + } + // Skip the dynamic options and set only the static camera options. + if (found == false) + { + std::string key; + double val; + + if (pnh_.searchParam(opt_name, key)) + { + double opt_val; + pnh_.getParam(key, val); + + // Validate and set the input values within the min-max range + if (val < o.min) + { + opt_val = o.min; + } + else if (val > o.max) + { + opt_val = o.max; + } + else + { + opt_val = val; + } + ROS_INFO_STREAM(nodelet_name_ << " - Static Options: " << opt_name << " = " << opt_val); + rs_set_device_option(rs_device_, o.opt, opt_val, &rs_error_); + checkError(); + } + } + } + } +} // end namespace + diff --git a/realsense_camera/src/realsense_camera_nodelet_r200.h b/realsense_camera/src/realsense_camera_nodelet_r200.h new file mode 100644 index 0000000000..525382aed1 --- /dev/null +++ b/realsense_camera/src/realsense_camera_nodelet_r200.h @@ -0,0 +1,73 @@ +/****************************************************************************** + Copyright (c) 2016, Intel Corporation + All rights reserved. + + Redistribution and use in source and binary forms, with or without + modification, are permitted provided that the following conditions are met: + + 1. Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + + 2. Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + + 3. Neither the name of the copyright holder nor the names of its contributors + may be used to endorse or promote products derived from this software without + specific prior written permission. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + *******************************************************************************/ + +#pragma once +#ifndef REALSENSE_NODELET_R200 +#define REALSENSE_NODELET_R200 + +#include + +#include "realsense_camera/camera_params_r200Config.h" +#include "realsense_camera_nodelet.h" + +namespace realsense_camera +{ + class RealsenseNodeletR200: public realsense_camera::RealsenseNodelet + { + public: + + // Initialize camera + void onInit(); + + protected: + // R200 Constants. + const rs_format IR2_FORMAT = RS_FORMAT_Y8; + const std::string DEFAULT_IR2_FRAME_ID = "camera_infrared2_frame"; + const char *IR2_TOPIC = "camera/infrared2/image_raw"; + const int NUM_STREAMS_R200 = 4; + + // Member Variables. + std::string ir2_frame_id_; + boost::shared_ptr> dynamic_reconf_server_; + + // Member Functions. + void enableDepthStream(); + void disableDepthStream(); + void enableInfrared2Stream(); + void disableInfrared2Stream(); + void setStreamOptions(); + void fillStreamEncoding(); + void allocateResources(); + void setStaticCameraOptions(); + void configCallback(realsense_camera::camera_params_r200Config &config, uint32_t level); + }; +} + +#endif From b345d6aa8f8998bfbda34c3584fa5c116c07cbcc Mon Sep 17 00:00:00 2001 From: Matthew Hansen Date: Tue, 14 Jun 2016 16:57:46 -0700 Subject: [PATCH 114/124] Added polling for camera Nodelet will now poll in a loop and try to connect to the specified camera every 5 seconds until the camera is found --- .../src/realsense_camera_nodelet.cpp | 72 +++++++++---------- 1 file changed, 36 insertions(+), 36 deletions(-) diff --git a/realsense_camera/src/realsense_camera_nodelet.cpp b/realsense_camera/src/realsense_camera_nodelet.cpp index 2b4ff383cd..2a91654412 100644 --- a/realsense_camera/src/realsense_camera_nodelet.cpp +++ b/realsense_camera/src/realsense_camera_nodelet.cpp @@ -78,6 +78,12 @@ namespace realsense_camera setStreamOptions(); + if (enable_depth_ == false && enable_color_ == false) + { + ROS_ERROR_STREAM(nodelet_name_ << " - None of the streams are enabled. Exiting!"); + ros::shutdown(); + } + // Set up the topics. frame_id_[RS_STREAM_DEPTH] = depth_optical_frame_id_; frame_id_[RS_STREAM_COLOR] = color_optical_frame_id_; @@ -93,29 +99,23 @@ namespace realsense_camera get_options_service_ = nh_.advertiseService(SETTINGS_SERVICE, &RealsenseNodelet::getCameraOptionValues, this); - bool connected = false; - - connected = connectToCamera(); - - if (connected == true) + // Poll for camera and connect if found + while (!connectToCamera()) { - // Start working thread. - stream_thread_ = - boost::shared_ptr (new boost::thread (boost::bind(&RealsenseNodelet::publishStreams, this))); + ROS_INFO_STREAM(nodelet_name_ << " - Sleeping 5 seconds then retrying to connect"); + ros::Duration(5).sleep(); + } - if (enable_tf_ == true) - { - transform_thread_ = - boost::shared_ptr(new boost::thread (boost::bind(&RealsenseNodelet::publishTransforms, this))); - } + // Start working thread. + stream_thread_ = + boost::shared_ptr (new boost::thread (boost::bind(&RealsenseNodelet::publishStreams, this))); - } - else + if (enable_tf_ == true) { - ROS_ERROR_STREAM(nodelet_name_ << " - Couldn't connect to camera! Shutting down..."); - ros::shutdown(); + transform_thread_ = + boost::shared_ptr(new boost::thread (boost::bind(&RealsenseNodelet::publishTransforms, this))); } -} + } /* *Protected Methods. @@ -223,27 +223,21 @@ namespace realsense_camera } } -void RealsenseNodelet::enableStreams() -{ - // Enable streams. - if (enable_color_ == true) - { - enableColorStream(); - } - if (enable_depth_ == true) + void RealsenseNodelet::enableStreams() { - enableDepthStream(); + // Enable streams. + if (enable_color_ == true) + { + enableColorStream(); + } + if (enable_depth_ == true) + { + enableDepthStream(); + } } -} bool RealsenseNodelet::connectToCamera() { - if (enable_depth_ == false && enable_color_ == false) - { - ROS_ERROR_STREAM(nodelet_name_ << " - None of the streams are enabled. Exiting!"); - return false; - } - rs_context_ = rs_create_context(RS_API_VERSION, &rs_error_); checkError(); @@ -253,7 +247,9 @@ void RealsenseNodelet::enableStreams() // Exit with error if no cameras are connected. if (num_of_cameras_ < 1) { - ROS_ERROR_STREAM(nodelet_name_ << " - No cameras detected. Exiting!"); + ROS_ERROR_STREAM(nodelet_name_ << " - No cameras detected!"); + rs_delete_context(rs_context_, &rs_error_); + checkError(); return false; } @@ -263,7 +259,9 @@ void RealsenseNodelet::enableStreams() // Exit with error if no serial number or usb_port_id is specified and multiple cameras are detected. if (serial_no_.empty() && usb_port_id_.empty() && num_of_cameras_ > 1) { - ROS_ERROR_STREAM(nodelet_name_ << " - Multiple cameras detected but no input serial_no or usb_port_id specified. Exiting!"); + ROS_ERROR_STREAM(nodelet_name_ << " - Multiple cameras detected but no input serial_no or usb_port_id specified"); + rs_delete_context(rs_context_, &rs_error_); + checkError(); return false; } @@ -291,6 +289,8 @@ void RealsenseNodelet::enableStreams() error_msg += "serial_no = " + serial_no_ + ", "; error_msg += "usb_port_id = " + usb_port_id_; ROS_ERROR_STREAM(nodelet_name_ << error_msg); + rs_delete_context(rs_context_, &rs_error_); + checkError(); return false; } From 639ddde603c978bb58255e195e7b7f7dc2e7d26d Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Mon, 20 Jun 2016 14:59:24 -0700 Subject: [PATCH 115/124] Fixed nodelet loading failure in test files --- .../test/realsense_r200_dynamic_camera_options_params.launch | 2 +- .../test/realsense_r200_static_camera_options_params.launch | 2 +- .../test/realsense_r200_stream_options_params.launch | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/realsense_camera/test/realsense_r200_dynamic_camera_options_params.launch b/realsense_camera/test/realsense_r200_dynamic_camera_options_params.launch index 8529efe0c4..a0b6247746 100644 --- a/realsense_camera/test/realsense_r200_dynamic_camera_options_params.launch +++ b/realsense_camera/test/realsense_r200_dynamic_camera_options_params.launch @@ -40,7 +40,7 @@ + args="load realsense_camera/RealsenseNodeletR200 standalone_nodelet"> diff --git a/realsense_camera/test/realsense_r200_static_camera_options_params.launch b/realsense_camera/test/realsense_r200_static_camera_options_params.launch index 0e18fedac3..84c35b2b9e 100644 --- a/realsense_camera/test/realsense_r200_static_camera_options_params.launch +++ b/realsense_camera/test/realsense_r200_static_camera_options_params.launch @@ -28,7 +28,7 @@ + args="load realsense_camera/RealsenseNodeletR200 standalone_nodelet"> diff --git a/realsense_camera/test/realsense_r200_stream_options_params.launch b/realsense_camera/test/realsense_r200_stream_options_params.launch index 4b10abad4f..9986d2525c 100644 --- a/realsense_camera/test/realsense_r200_stream_options_params.launch +++ b/realsense_camera/test/realsense_r200_stream_options_params.launch @@ -25,7 +25,7 @@ + args="load realsense_camera/RealsenseNodeletR200 standalone_nodelet"> From 2ac8a9478423291eaec61a443592b9438efe6686 Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Mon, 20 Jun 2016 15:21:26 -0700 Subject: [PATCH 116/124] Renamed source files and classes. --- realsense_camera/CMakeLists.txt | 24 ++++----- realsense_camera/README.md | 4 +- ...camera_params_r200.cfg => r200_params.cfg} | 2 +- ...realsense_r200_multiple_cameras.launch.xml | 2 +- .../realsense_r200_nodelet.launch.xml | 4 +- .../launch/realsense_r200_navigation.launch | 4 +- ...ense_r200_nodelet_standalone_manual.launch | 4 +- ...ense_r200_nodelet_standalone_preset.launch | 4 +- ...odelet_plugins.xml => nodelet_plugins.xml} | 2 +- realsense_camera/package.xml | 2 +- ...se_camera_nodelet.cpp => base_nodelet.cpp} | 52 +++++++++---------- ...lsense_camera_nodelet.h => base_nodelet.h} | 8 +-- ...mera_nodelet_r200.cpp => r200_nodelet.cpp} | 48 ++++++++--------- ...e_camera_nodelet_r200.h => r200_nodelet.h} | 14 ++--- ...e_camera_test_node.cpp => camera_core.cpp} | 5 +- ...sense_camera_test_node.h => camera_core.h} | 18 +++---- .../test/realsense_r200_color_only.test | 2 +- .../test/realsense_r200_depth_only.test | 2 +- ..._r200_dynamic_camera_options_params.launch | 6 +-- .../test/realsense_r200_resolution.test | 2 +- .../test/realsense_r200_rgbd.test | 2 +- ...e_r200_static_camera_options_params.launch | 6 +-- ...ealsense_r200_stream_options_params.launch | 6 +-- ...era_test_rgbd_node.cpp => rgbd_topics.cpp} | 5 +- ..._camera_test_rgbd_node.h => rgbd_topics.h} | 0 25 files changed, 115 insertions(+), 113 deletions(-) rename realsense_camera/cfg/{camera_params_r200.cfg => r200_params.cfg} (97%) rename realsense_camera/{realsense_camera_nodelet_plugins.xml => nodelet_plugins.xml} (52%) rename realsense_camera/src/{realsense_camera_nodelet.cpp => base_nodelet.cpp} (95%) rename realsense_camera/src/{realsense_camera_nodelet.h => base_nodelet.h} (98%) rename realsense_camera/src/{realsense_camera_nodelet_r200.cpp => r200_nodelet.cpp} (85%) rename realsense_camera/src/{realsense_camera_nodelet_r200.h => r200_nodelet.h} (86%) rename realsense_camera/test/{realsense_camera_test_node.cpp => camera_core.cpp} (99%) rename realsense_camera/test/{realsense_camera_test_node.h => camera_core.h} (92%) rename realsense_camera/test/{realsense_camera_test_rgbd_node.cpp => rgbd_topics.cpp} (97%) rename realsense_camera/test/{realsense_camera_test_rgbd_node.h => rgbd_topics.h} (100%) diff --git a/realsense_camera/CMakeLists.txt b/realsense_camera/CMakeLists.txt index 99bf966986..2a14aee2a7 100644 --- a/realsense_camera/CMakeLists.txt +++ b/realsense_camera/CMakeLists.txt @@ -40,36 +40,36 @@ generate_messages( #add dynamic reconfigure api generate_dynamic_reconfigure_options( - cfg/camera_params_r200.cfg + cfg/r200_params.cfg ) include_directories( ${catkin_INCLUDE_DIRS} ) -add_library(realsense_camera_nodelet src/realsense_camera_nodelet.cpp src/realsense_camera_nodelet_r200.cpp) -target_link_libraries(realsense_camera_nodelet +add_library(${PROJECT_NAME}_nodelet src/base_nodelet.cpp src/r200_nodelet.cpp) +target_link_libraries(${PROJECT_NAME}_nodelet ${catkin_LIBRARIES} realsense ) -add_dependencies(realsense_camera_nodelet realsense_camera_generate_messages_cpp ${PROJECT_NAME}_gencfg) +add_dependencies(${PROJECT_NAME}_nodelet ${PROJECT_NAME}_generate_messages_cpp ${PROJECT_NAME}_gencfg) -add_executable(realsense_camera_test test/realsense_camera_test_node.cpp) -target_link_libraries(realsense_camera_test +add_executable(tests_camera_core test/camera_core.cpp) +target_link_libraries(tests_camera_core ${catkin_LIBRARIES} ${GTEST_LIBRARIES} ) -add_dependencies(realsense_camera_test realsense_camera_generate_messages_cpp ${PROJECT_NAME}_gencfg) +add_dependencies(tests_camera_core ${PROJECT_NAME}_generate_messages_cpp ${PROJECT_NAME}_gencfg) -add_executable(realsense_camera_test_rgbd test/realsense_camera_test_rgbd_node.cpp) -target_link_libraries(realsense_camera_test_rgbd +add_executable(tests_rgbd_topics test/rgbd_topics.cpp) +target_link_libraries(tests_rgbd_topics ${catkin_LIBRARIES} ${GTEST_LIBRARIES} ) -add_dependencies(realsense_camera_test_rgbd realsense_camera_generate_messages_cpp) +add_dependencies(tests_rgbd_topics ${PROJECT_NAME}_generate_messages_cpp) # Install nodelet library -install(TARGETS realsense_camera_nodelet LIBRARY +install(TARGETS ${PROJECT_NAME}_nodelet LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} ) @@ -84,6 +84,6 @@ install(DIRECTORY rviz/ ) # Install xml files -install(FILES package.xml realsense_camera_nodelet_plugins.xml +install(FILES package.xml nodelet_plugins.xml DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} ) diff --git a/realsense_camera/README.md b/realsense_camera/README.md index 3c9c60a6eb..8b22f4b438 100644 --- a/realsense_camera/README.md +++ b/realsense_camera/README.md @@ -178,7 +178,7 @@ Command to launch GUI: Command to change dynamic parameters using commandline: $ rosrun dynamic_reconfigure dynparam set / - E.g. $ rosrun dynamic_reconfigure dynparam set /RealsenseNodeletR200 color_backlight_compensation 2 + E.g. $ rosrun dynamic_reconfigure dynparam set /R200Nodelet color_backlight_compensation 2 ###Running the R200 nodelet: @@ -187,7 +187,7 @@ Use the following command to launch the camera nodelet. You will notice the came $ roslaunch realsense_camera realsense_r200_nodelet_standalone_preset.launch -If you would like to create or use your own launch files, the nodelet name for the R200 camera is RealsenseNodeletR200. See the sample launch files for examples of how to launch the nodelet. +If you would like to create or use your own launch files, the nodelet name for the R200 camera is R200Nodelet. See the sample launch files for examples of how to launch the nodelet. View using RVIZ: diff --git a/realsense_camera/cfg/camera_params_r200.cfg b/realsense_camera/cfg/r200_params.cfg similarity index 97% rename from realsense_camera/cfg/camera_params_r200.cfg rename to realsense_camera/cfg/r200_params.cfg index 496e9f9c2e..645acaffd6 100755 --- a/realsense_camera/cfg/camera_params_r200.cfg +++ b/realsense_camera/cfg/r200_params.cfg @@ -27,4 +27,4 @@ gen.add("r200_auto_exposure_bottom_edge", int_t, 0, "Auto Exp gen.add("r200_auto_exposure_left_edge", int_t, 0, "Auto Exposure Left Edge", 0, 0, 639) gen.add("r200_auto_exposure_right_edge", int_t, 0, "Auto Exposure Right Edge", 639, 0, 639) -exit(gen.generate(PACKAGE, "realsense_camera", "camera_params_r200")) +exit(gen.generate(PACKAGE, "realsense_camera", "r200_params")) diff --git a/realsense_camera/launch/includes/realsense_r200_multiple_cameras.launch.xml b/realsense_camera/launch/includes/realsense_r200_multiple_cameras.launch.xml index bf1b5f5336..aec4b6c0bf 100644 --- a/realsense_camera/launch/includes/realsense_r200_multiple_cameras.launch.xml +++ b/realsense_camera/launch/includes/realsense_r200_multiple_cameras.launch.xml @@ -6,7 +6,7 @@ + args="load realsense_camera/R200Nodelet $(arg manager)"> diff --git a/realsense_camera/launch/includes/realsense_r200_nodelet.launch.xml b/realsense_camera/launch/includes/realsense_r200_nodelet.launch.xml index 2b0e7fef03..608b4bc538 100644 --- a/realsense_camera/launch/includes/realsense_r200_nodelet.launch.xml +++ b/realsense_camera/launch/includes/realsense_r200_nodelet.launch.xml @@ -34,8 +34,8 @@ - + diff --git a/realsense_camera/launch/realsense_r200_navigation.launch b/realsense_camera/launch/realsense_r200_navigation.launch index bff55143e0..c98e022896 100644 --- a/realsense_camera/launch/realsense_r200_navigation.launch +++ b/realsense_camera/launch/realsense_r200_navigation.launch @@ -9,8 +9,8 @@ - + diff --git a/realsense_camera/launch/realsense_r200_nodelet_standalone_manual.launch b/realsense_camera/launch/realsense_r200_nodelet_standalone_manual.launch index 6169769da4..da4eacde9d 100644 --- a/realsense_camera/launch/realsense_r200_nodelet_standalone_manual.launch +++ b/realsense_camera/launch/realsense_r200_nodelet_standalone_manual.launch @@ -16,8 +16,8 @@ - + diff --git a/realsense_camera/launch/realsense_r200_nodelet_standalone_preset.launch b/realsense_camera/launch/realsense_r200_nodelet_standalone_preset.launch index ccda09f5c6..57dce5b176 100644 --- a/realsense_camera/launch/realsense_r200_nodelet_standalone_preset.launch +++ b/realsense_camera/launch/realsense_r200_nodelet_standalone_preset.launch @@ -9,8 +9,8 @@ - + diff --git a/realsense_camera/realsense_camera_nodelet_plugins.xml b/realsense_camera/nodelet_plugins.xml similarity index 52% rename from realsense_camera/realsense_camera_nodelet_plugins.xml rename to realsense_camera/nodelet_plugins.xml index c62d71c5dd..f6c7e0472e 100644 --- a/realsense_camera/realsense_camera_nodelet_plugins.xml +++ b/realsense_camera/nodelet_plugins.xml @@ -1,5 +1,5 @@ - + Intel(R) RealSense(TM) R200 Camera nodelet. diff --git a/realsense_camera/package.xml b/realsense_camera/package.xml index 03839dbf22..b254b4d421 100644 --- a/realsense_camera/package.xml +++ b/realsense_camera/package.xml @@ -44,6 +44,6 @@ rgbd_launch - + diff --git a/realsense_camera/src/realsense_camera_nodelet.cpp b/realsense_camera/src/base_nodelet.cpp similarity index 95% rename from realsense_camera/src/realsense_camera_nodelet.cpp rename to realsense_camera/src/base_nodelet.cpp index 2a91654412..cd6c4ae7a2 100644 --- a/realsense_camera/src/realsense_camera_nodelet.cpp +++ b/realsense_camera/src/base_nodelet.cpp @@ -28,19 +28,19 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *******************************************************************************/ -#include "realsense_camera_nodelet.h" +#include "base_nodelet.h" using namespace cv; using namespace std; -PLUGINLIB_EXPORT_CLASS (realsense_camera::RealsenseNodelet, nodelet::Nodelet) +PLUGINLIB_EXPORT_CLASS (realsense_camera::BaseNodelet, nodelet::Nodelet) namespace realsense_camera { /* * Public Methods. */ - RealsenseNodelet::~RealsenseNodelet() + BaseNodelet::~BaseNodelet() { stream_thread_->join(); @@ -65,7 +65,7 @@ namespace realsense_camera /* * Initialize the realsense camera */ - void RealsenseNodelet::onInit() + void BaseNodelet::onInit() { // Set default configurations. is_device_started_ = false; @@ -97,7 +97,7 @@ namespace realsense_camera pointcloud_publisher_ = nh_.advertise(PC_TOPIC, 1); - get_options_service_ = nh_.advertiseService(SETTINGS_SERVICE, &RealsenseNodelet::getCameraOptionValues, this); + get_options_service_ = nh_.advertiseService(SETTINGS_SERVICE, &BaseNodelet::getCameraOptionValues, this); // Poll for camera and connect if found while (!connectToCamera()) @@ -108,19 +108,19 @@ namespace realsense_camera // Start working thread. stream_thread_ = - boost::shared_ptr (new boost::thread (boost::bind(&RealsenseNodelet::publishStreams, this))); + boost::shared_ptr (new boost::thread (boost::bind(&BaseNodelet::publishStreams, this))); if (enable_tf_ == true) { transform_thread_ = - boost::shared_ptr(new boost::thread (boost::bind(&RealsenseNodelet::publishTransforms, this))); + boost::shared_ptr(new boost::thread (boost::bind(&BaseNodelet::publishTransforms, this))); } } /* *Protected Methods. */ - void RealsenseNodelet::enableColorStream() + void BaseNodelet::enableColorStream() { // Enable streams. if (mode_.compare ("manual") == 0) @@ -143,7 +143,7 @@ namespace realsense_camera } } - void RealsenseNodelet::enableDepthStream() + void BaseNodelet::enableDepthStream() { // Enable streams. if (mode_.compare ("manual") == 0) @@ -168,7 +168,7 @@ namespace realsense_camera enableInfraredStream(); } - void RealsenseNodelet::enableInfraredStream() + void BaseNodelet::enableInfraredStream() { // Enable streams. if (mode_.compare ("manual") == 0) @@ -191,7 +191,7 @@ namespace realsense_camera } } - void RealsenseNodelet::disableDepthStream() + void BaseNodelet::disableDepthStream() { // disable depth stream ROS_INFO_STREAM(nodelet_name_ << " - Disabling Depth stream"); @@ -202,14 +202,14 @@ namespace realsense_camera disableInfraredStream(); } - void RealsenseNodelet::disableInfraredStream() + void BaseNodelet::disableInfraredStream() { ROS_INFO_STREAM(nodelet_name_ << " - Disabling Infrared stream"); rs_disable_stream(rs_device_, RS_STREAM_INFRARED, &rs_error_); checkError(); } - void RealsenseNodelet::checkError() + void BaseNodelet::checkError() { if (rs_error_) { @@ -223,7 +223,7 @@ namespace realsense_camera } } - void RealsenseNodelet::enableStreams() + void BaseNodelet::enableStreams() { // Enable streams. if (enable_color_ == true) @@ -236,7 +236,7 @@ namespace realsense_camera } } - bool RealsenseNodelet::connectToCamera() + bool BaseNodelet::connectToCamera() { rs_context_ = rs_create_context(RS_API_VERSION, &rs_error_); checkError(); @@ -317,7 +317,7 @@ namespace realsense_camera return true; } - void RealsenseNodelet::listCameras() + void BaseNodelet::listCameras() { // print list of detected cameras std::string detected_camera_msg = " - Detected the following cameras:"; @@ -339,7 +339,7 @@ namespace realsense_camera /* * Gets the options supported by the camera along with their min, max and step values. */ - void RealsenseNodelet::getCameraOptions() + void BaseNodelet::getCameraOptions() { for (int i = 0; i < RS_OPTION_COUNT; ++i) { @@ -361,7 +361,7 @@ namespace realsense_camera /* * Define buffer for images and prepare camera info for each enabled stream. */ - void RealsenseNodelet::allocateResources() + void BaseNodelet::allocateResources() { // Prepare camera for enabled streams (color/depth/infrared) fillStreamEncoding(); @@ -374,7 +374,7 @@ namespace realsense_camera /* * Prepare camera_info for each enabled stream. */ - void RealsenseNodelet::prepareStreamCalibData(rs_stream rs_strm) + void BaseNodelet::prepareStreamCalibData(rs_stream rs_strm) { uint32_t stream_index = (uint32_t) rs_strm; rs_intrinsics intrinsic; @@ -442,7 +442,7 @@ namespace realsense_camera /* * Get the latest values of the camera options. */ - bool RealsenseNodelet::getCameraOptionValues(realsense_camera::cameraConfiguration::Request & req, + bool BaseNodelet::getCameraOptionValues(realsense_camera::cameraConfiguration::Request & req, realsense_camera::cameraConfiguration::Response & res) { std::string get_options_result_str; @@ -464,7 +464,7 @@ namespace realsense_camera /* * Set the stream options based on input params. */ - void RealsenseNodelet::setStreamOptions() + void BaseNodelet::setStreamOptions() { pnh_.getParam("serial_no", serial_no_); pnh_.getParam("usb_port_id", usb_port_id_); @@ -492,7 +492,7 @@ namespace realsense_camera /* * Copy frame data from realsense to member cv images. */ - void RealsenseNodelet::prepareStreamData(rs_stream rs_strm) + void BaseNodelet::prepareStreamData(rs_stream rs_strm) { if (rs_strm == RS_STREAM_DEPTH) { @@ -506,7 +506,7 @@ namespace realsense_camera /* * Populate the encodings for each stream. */ - void RealsenseNodelet::fillStreamEncoding() + void BaseNodelet::fillStreamEncoding() { stream_encoding_[(uint32_t) RS_STREAM_COLOR] = "rgb8"; stream_step_[(uint32_t) RS_STREAM_COLOR] = color_width_ * sizeof (unsigned char) * 3; @@ -519,7 +519,7 @@ namespace realsense_camera /* * Publish streams. */ - void RealsenseNodelet::publishStreams() + void BaseNodelet::publishStreams() { while (ros::ok()) { @@ -626,7 +626,7 @@ namespace realsense_camera /* * Publish pointcloud. */ - void RealsenseNodelet::publishPointCloud (cv::Mat & image_color) + void BaseNodelet::publishPointCloud (cv::Mat & image_color) { // Publish pointcloud only if there is at least one subscriber. if (pointcloud_publisher_.getNumSubscribers() > 0) @@ -739,7 +739,7 @@ namespace realsense_camera /* * Publish camera transforms */ - void RealsenseNodelet::publishTransforms() + void BaseNodelet::publishTransforms() { // publish transforms for the cameras ROS_INFO_STREAM(nodelet_name_ << " - Publishing camera transforms"); diff --git a/realsense_camera/src/realsense_camera_nodelet.h b/realsense_camera/src/base_nodelet.h similarity index 98% rename from realsense_camera/src/realsense_camera_nodelet.h rename to realsense_camera/src/base_nodelet.h index bab69a30de..c43d905858 100644 --- a/realsense_camera/src/realsense_camera_nodelet.h +++ b/realsense_camera/src/base_nodelet.h @@ -29,8 +29,8 @@ *******************************************************************************/ #pragma once -#ifndef REALSENSE_NODELET -#define REALSENSE_NODELET +#ifndef BASE_NODELET +#define BASE_NODELET #include #include @@ -65,13 +65,13 @@ namespace realsense_camera { - class RealsenseNodelet: public nodelet::Nodelet + class BaseNodelet: public nodelet::Nodelet { public: // Interfaces. virtual void onInit(); - virtual ~RealsenseNodelet(); + virtual ~BaseNodelet(); virtual void publishTransforms(); virtual void publishStreams(); virtual bool getCameraOptionValues(realsense_camera::cameraConfiguration::Request & req, realsense_camera::cameraConfiguration::Response & res); diff --git a/realsense_camera/src/realsense_camera_nodelet_r200.cpp b/realsense_camera/src/r200_nodelet.cpp similarity index 85% rename from realsense_camera/src/realsense_camera_nodelet_r200.cpp rename to realsense_camera/src/r200_nodelet.cpp index 1a402e5c55..50f45f92f5 100644 --- a/realsense_camera/src/realsense_camera_nodelet_r200.cpp +++ b/realsense_camera/src/r200_nodelet.cpp @@ -28,9 +28,9 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *******************************************************************************/ -#include "realsense_camera_nodelet_r200.h" +#include "r200_nodelet.h" -PLUGINLIB_EXPORT_CLASS (realsense_camera::RealsenseNodeletR200, nodelet::Nodelet) +PLUGINLIB_EXPORT_CLASS (realsense_camera::R200Nodelet, nodelet::Nodelet) namespace realsense_camera { @@ -41,7 +41,7 @@ namespace realsense_camera /* * Initialize the realsense camera */ - void RealsenseNodeletR200::onInit() + void R200Nodelet::onInit() { // set member vars used in base class nodelet_name_ = getName(); @@ -51,10 +51,10 @@ namespace realsense_camera // create dynamic reconfigure server - this must be done before calling base class onInit() // onInit() calls setStaticCameraOptions() which relies on this being set already - dynamic_reconf_server_.reset(new dynamic_reconfigure::Server(pnh_)); + dynamic_reconf_server_.reset(new dynamic_reconfigure::Server(pnh_)); // call base class onInit() method - RealsenseNodelet::onInit(); + BaseNodelet::onInit(); // Set up the IR2 frame and topics frame_id_[RS_STREAM_INFRARED2] = ir2_frame_id_; @@ -62,29 +62,29 @@ namespace realsense_camera camera_publisher_[RS_STREAM_INFRARED2] = it.advertiseCamera(IR2_TOPIC, 1); // setCallback can only be called after rs_device_ is set by base class connectToCamera() - dynamic_reconf_server_->setCallback(boost::bind(&RealsenseNodeletR200::configCallback, this, _1, _2)); + dynamic_reconf_server_->setCallback(boost::bind(&R200Nodelet::configCallback, this, _1, _2)); } /* *Protected Methods. */ - void RealsenseNodeletR200::enableDepthStream() + void R200Nodelet::enableDepthStream() { // call the base class method first - RealsenseNodelet::enableDepthStream(); + BaseNodelet::enableDepthStream(); // enable IR2 stream enableInfrared2Stream(); } - void RealsenseNodeletR200::disableDepthStream() + void R200Nodelet::disableDepthStream() { // call the base class method first - RealsenseNodelet::disableDepthStream(); + BaseNodelet::disableDepthStream(); // disable IR2 stream disableInfrared2Stream(); } - void RealsenseNodeletR200::enableInfrared2Stream() + void R200Nodelet::enableInfrared2Stream() { // Enable streams. if (mode_.compare ("manual") == 0) @@ -107,14 +107,14 @@ namespace realsense_camera } } - void RealsenseNodeletR200::disableInfrared2Stream() + void R200Nodelet::disableInfrared2Stream() { ROS_INFO_STREAM(nodelet_name_ << " - Disabling Infrared2 stream"); rs_disable_stream(rs_device_, RS_STREAM_INFRARED2, &rs_error_); checkError(); } - void RealsenseNodeletR200::configCallback(realsense_camera::camera_params_r200Config &config, uint32_t level) + void R200Nodelet::configCallback(realsense_camera::r200_paramsConfig &config, uint32_t level) { // Set common options rs_set_device_option(rs_device_, RS_OPTION_COLOR_BACKLIGHT_COMPENSATION, config.color_backlight_compensation, 0); @@ -190,10 +190,10 @@ namespace realsense_camera /* * Define buffer for images and prepare camera info for each enabled stream. */ - void RealsenseNodeletR200::allocateResources() + void R200Nodelet::allocateResources() { // call base class method first - RealsenseNodelet::allocateResources(); + BaseNodelet::allocateResources(); // set IR2 image buffer image_[(uint32_t) RS_STREAM_INFRARED2] = cv::Mat(depth_height_, depth_width_, CV_8UC1, cv::Scalar (0)); } @@ -201,10 +201,10 @@ namespace realsense_camera /* * Set the stream options based on input params. */ - void RealsenseNodeletR200::setStreamOptions() + void R200Nodelet::setStreamOptions() { // call base class method first - RealsenseNodelet::setStreamOptions(); + BaseNodelet::setStreamOptions(); // setup R200 specific frame pnh_.param("ir2_frame_id", ir2_frame_id_, DEFAULT_IR2_FRAME_ID); } @@ -212,10 +212,10 @@ namespace realsense_camera /* * Populate the encodings for each stream. */ - void RealsenseNodeletR200::fillStreamEncoding() + void R200Nodelet::fillStreamEncoding() { // Call base class method first - RealsenseNodelet::fillStreamEncoding(); + BaseNodelet::fillStreamEncoding(); // Setup IR2 stream stream_encoding_[(uint32_t) RS_STREAM_INFRARED2] = sensor_msgs::image_encodings::TYPE_8UC1; stream_step_[(uint32_t) RS_STREAM_INFRARED2] = depth_width_ * sizeof (unsigned char); @@ -224,15 +224,15 @@ namespace realsense_camera /* * Set the static camera options. */ - void RealsenseNodeletR200::setStaticCameraOptions() + void R200Nodelet::setStaticCameraOptions() { ROS_INFO_STREAM(nodelet_name_ << " - Setting camera options"); // Get dynamic options from the dynamic reconfigure server. - realsense_camera::camera_params_r200Config params_config; + realsense_camera::r200_paramsConfig params_config; dynamic_reconf_server_->getConfigDefault(params_config); - std::vector param_desc = params_config.__getParamDescriptions__(); + std::vector param_desc = params_config.__getParamDescriptions__(); // Iterate through the supported camera options for (CameraOptions o: camera_options_) @@ -240,8 +240,8 @@ namespace realsense_camera std::string opt_name = rs_option_to_string(o.opt); bool found = false; - std::vector::iterator it; - for (realsense_camera::camera_params_r200Config::AbstractParamDescriptionConstPtr param_desc_ptr: param_desc) + std::vector::iterator it; + for (realsense_camera::r200_paramsConfig::AbstractParamDescriptionConstPtr param_desc_ptr: param_desc) { std::transform(opt_name.begin(), opt_name.end(), opt_name.begin(), ::tolower); if (opt_name.compare((* param_desc_ptr).name) == 0) diff --git a/realsense_camera/src/realsense_camera_nodelet_r200.h b/realsense_camera/src/r200_nodelet.h similarity index 86% rename from realsense_camera/src/realsense_camera_nodelet_r200.h rename to realsense_camera/src/r200_nodelet.h index 525382aed1..64f5ae31d3 100644 --- a/realsense_camera/src/realsense_camera_nodelet_r200.h +++ b/realsense_camera/src/r200_nodelet.h @@ -29,17 +29,17 @@ *******************************************************************************/ #pragma once -#ifndef REALSENSE_NODELET_R200 -#define REALSENSE_NODELET_R200 +#ifndef R200_NODELET +#define R200_NODELET #include -#include "realsense_camera/camera_params_r200Config.h" -#include "realsense_camera_nodelet.h" +#include "realsense_camera/r200_paramsConfig.h" +#include "base_nodelet.h" namespace realsense_camera { - class RealsenseNodeletR200: public realsense_camera::RealsenseNodelet + class R200Nodelet: public realsense_camera::BaseNodelet { public: @@ -55,7 +55,7 @@ namespace realsense_camera // Member Variables. std::string ir2_frame_id_; - boost::shared_ptr> dynamic_reconf_server_; + boost::shared_ptr> dynamic_reconf_server_; // Member Functions. void enableDepthStream(); @@ -66,7 +66,7 @@ namespace realsense_camera void fillStreamEncoding(); void allocateResources(); void setStaticCameraOptions(); - void configCallback(realsense_camera::camera_params_r200Config &config, uint32_t level); + void configCallback(realsense_camera::r200_paramsConfig &config, uint32_t level); }; } diff --git a/realsense_camera/test/realsense_camera_test_node.cpp b/realsense_camera/test/camera_core.cpp similarity index 99% rename from realsense_camera/test/realsense_camera_test_node.cpp rename to realsense_camera/test/camera_core.cpp index 6908baf48f..138e01f55c 100644 --- a/realsense_camera/test/realsense_camera_test_node.cpp +++ b/realsense_camera/test/camera_core.cpp @@ -29,7 +29,7 @@ *******************************************************************************/ #include "gtest/gtest.h" -#include "realsense_camera_test_node.h" +#include "camera_core.h" using namespace std; @@ -622,7 +622,7 @@ void fillConfigMap(int argc, char **argv) } } -int main(int argc, char **argv) +int main(int argc, char **argv) try { testing::InitGoogleTest(&argc, argv); ros::init(argc, argv, "utest"); @@ -651,3 +651,4 @@ int main(int argc, char **argv) return RUN_ALL_TESTS(); } +catch(...) {} // catch the "testing::internal::::ClassUniqueToAlwaysTrue" from gtest diff --git a/realsense_camera/test/realsense_camera_test_node.h b/realsense_camera/test/camera_core.h similarity index 92% rename from realsense_camera/test/realsense_camera_test_node.h rename to realsense_camera/test/camera_core.h index a2bb912e80..cbaeaed122 100644 --- a/realsense_camera/test/realsense_camera_test_node.h +++ b/realsense_camera/test/camera_core.h @@ -8,12 +8,12 @@ 1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer. - 2. Redistributions in binary form must reproduce the above copyright notice, - this list of conditions and the following disclaimer in the documentation + 2. Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution. - 3. Neither the name of the copyright holder nor the names of its contributors - may be used to endorse or promote products derived from this software without + 3. Neither the name of the copyright holder nor the names of its contributors + may be used to endorse or promote products derived from this software without specific prior written permission. THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" @@ -76,10 +76,10 @@ int g_color_height_exp = 0; int g_color_width_exp = 0; int g_depth_height_exp = 0; int g_depth_width_exp = 0; -uint32_t g_depth_step_exp; // Expected depth step. -uint32_t g_color_step_exp; // Expected color step. -uint32_t g_infrared1_step_exp; // Expected infrared1 step. -uint32_t g_infrared2_step_exp; // Expected infrared2 step. +uint32_t g_depth_step_exp; // Expected depth step. +uint32_t g_color_step_exp; // Expected color step. +uint32_t g_infrared1_step_exp; // Expected infrared1 step. +uint32_t g_infrared2_step_exp; // Expected infrared2 step. bool g_enable_color = true; bool g_enable_depth = true; @@ -109,7 +109,7 @@ float g_pc_depth_avg = 0; int g_height_recv[R200_STREAMS_COUNT] = {0}; int g_width_recv[R200_STREAMS_COUNT] = {0}; -uint32_t g_step_recv[R200_STREAMS_COUNT] = {0}; // Received stream step. +uint32_t g_step_recv[R200_STREAMS_COUNT] = {0}; // Received stream step. std::string g_encoding_recv[R200_STREAMS_COUNT]; // Expected stream encoding. diff --git a/realsense_camera/test/realsense_r200_color_only.test b/realsense_camera/test/realsense_r200_color_only.test index 29f001c030..5e1867033f 100644 --- a/realsense_camera/test/realsense_r200_color_only.test +++ b/realsense_camera/test/realsense_r200_color_only.test @@ -4,6 +4,6 @@ - diff --git a/realsense_camera/test/realsense_r200_depth_only.test b/realsense_camera/test/realsense_r200_depth_only.test index 205ae84195..be924c0b17 100644 --- a/realsense_camera/test/realsense_r200_depth_only.test +++ b/realsense_camera/test/realsense_r200_depth_only.test @@ -4,6 +4,6 @@ - diff --git a/realsense_camera/test/realsense_r200_dynamic_camera_options_params.launch b/realsense_camera/test/realsense_r200_dynamic_camera_options_params.launch index a0b6247746..f1846e1de8 100644 --- a/realsense_camera/test/realsense_r200_dynamic_camera_options_params.launch +++ b/realsense_camera/test/realsense_r200_dynamic_camera_options_params.launch @@ -3,7 +3,7 @@ Steps: roslaunch realsense_camera realsense_r200_dynamic_camera_options_params.launch - rosrun realsense_camera realsense_camera_test color_backlight_compensation 3 color_brightness 10 color_contrast 16 color_gain 18 color_gamma 100 color_hue 20 color_saturation 21 color_sharpness 7 color_enable_auto_white_balance 0 color_white_balance 3000 r200_lr_gain 200 r200_emitter_enabled 1 r200_lr_exposure 27 + rosrun realsense_camera tests_camera_core color_backlight_compensation 3 color_brightness 10 color_contrast 16 color_gain 18 color_gamma 100 color_hue 20 color_saturation 21 color_sharpness 7 color_enable_auto_white_balance 0 color_white_balance 3000 r200_lr_gain 200 r200_emitter_enabled 1 r200_lr_exposure 27 Verify that the "testCameraOptions" test pass. --> @@ -39,8 +39,8 @@ - + diff --git a/realsense_camera/test/realsense_r200_resolution.test b/realsense_camera/test/realsense_r200_resolution.test index 8477438e6e..ef34a1f5cb 100644 --- a/realsense_camera/test/realsense_r200_resolution.test +++ b/realsense_camera/test/realsense_r200_resolution.test @@ -9,6 +9,6 @@ - diff --git a/realsense_camera/test/realsense_r200_rgbd.test b/realsense_camera/test/realsense_r200_rgbd.test index 2713f936d0..8ed6427103 100644 --- a/realsense_camera/test/realsense_r200_rgbd.test +++ b/realsense_camera/test/realsense_r200_rgbd.test @@ -3,5 +3,5 @@ - + diff --git a/realsense_camera/test/realsense_r200_static_camera_options_params.launch b/realsense_camera/test/realsense_r200_static_camera_options_params.launch index 84c35b2b9e..c362384a7f 100644 --- a/realsense_camera/test/realsense_r200_static_camera_options_params.launch +++ b/realsense_camera/test/realsense_r200_static_camera_options_params.launch @@ -3,7 +3,7 @@ Steps: roslaunch realsense_camera realsense_r200_static_camera_options_params.launch - rosrun realsense_camera realsense_camera_test r200_depth_units 2 r200_depth_clamp_min 3 r200_depth_clamp_max 4 r200_depth_control_estimate_median_decrement 5 r200_depth_control_estimate_median_increment 6 r200_depth_control_median_threshold 7 r200_depth_control_score_minimum_threshold 8 r200_depth_control_score_maximum_threshold 9 r200_depth_control_texture_count_threshold 10 r200_depth_control_texture_difference_threshold 11 r200_depth_control_second_peak_threshold 12 r200_depth_control_neighbor_threshold 13 r200_depth_control_lr_threshold 14 + rosrun realsense_camera tests_camera_core r200_depth_units 2 r200_depth_clamp_min 3 r200_depth_clamp_max 4 r200_depth_control_estimate_median_decrement 5 r200_depth_control_estimate_median_increment 6 r200_depth_control_median_threshold 7 r200_depth_control_score_minimum_threshold 8 r200_depth_control_score_maximum_threshold 9 r200_depth_control_texture_count_threshold 10 r200_depth_control_texture_difference_threshold 11 r200_depth_control_second_peak_threshold 12 r200_depth_control_neighbor_threshold 13 r200_depth_control_lr_threshold 14 Verify that the "testCameraOptions" test pass. --> @@ -27,8 +27,8 @@ - + diff --git a/realsense_camera/test/realsense_r200_stream_options_params.launch b/realsense_camera/test/realsense_r200_stream_options_params.launch index 9986d2525c..4175ef4df7 100644 --- a/realsense_camera/test/realsense_r200_stream_options_params.launch +++ b/realsense_camera/test/realsense_r200_stream_options_params.launch @@ -3,7 +3,7 @@ Steps: roslaunch realsense_camera realsense_r200_stream_options_params.launch - rosrun realsense_camera realsense_camera_test mode manual enable_depth false enable_color true enable_pointcloud true enable_tf true depth_width 320 depth_height 240 color_width 320 color_height 240 depth_fps 60 color_fps 60 camera R200 + rosrun realsense_camera tests_camera_core mode manual enable_depth false enable_color true enable_pointcloud true enable_tf true depth_width 320 depth_height 240 color_width 320 color_height 240 depth_fps 60 color_fps 60 camera R200 Verify that all the tests pass. --> @@ -24,8 +24,8 @@ - + diff --git a/realsense_camera/test/realsense_camera_test_rgbd_node.cpp b/realsense_camera/test/rgbd_topics.cpp similarity index 97% rename from realsense_camera/test/realsense_camera_test_rgbd_node.cpp rename to realsense_camera/test/rgbd_topics.cpp index 0ff6d23295..b3986e3880 100644 --- a/realsense_camera/test/realsense_camera_test_rgbd_node.cpp +++ b/realsense_camera/test/rgbd_topics.cpp @@ -28,7 +28,7 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *******************************************************************************/ -#include "realsense_camera_test_rgbd_node.h" +#include "rgbd_topics.h" using namespace std; void topic0Callback(const sensor_msgs::ImageConstPtr msg) @@ -227,7 +227,7 @@ void setTopics() depth_reg_sw_reg_image_rect = "/" + camera + "/" + depth_registered + "/" + DEPTH_REG_SW_REG_IMAGE_RECT; } -int main(int argc, char **argv) +int main(int argc, char **argv) try { testing::InitGoogleTest(&argc, argv); ros::init(argc, argv, "utest"); @@ -259,3 +259,4 @@ int main(int argc, char **argv) return RUN_ALL_TESTS(); } +catch(...) {} // catch the "testing::internal::::ClassUniqueToAlwaysTrue" from gtest diff --git a/realsense_camera/test/realsense_camera_test_rgbd_node.h b/realsense_camera/test/rgbd_topics.h similarity index 100% rename from realsense_camera/test/realsense_camera_test_rgbd_node.h rename to realsense_camera/test/rgbd_topics.h From 52e2c87b72c537f3e998dacc7c20a753afbeb9f6 Mon Sep 17 00:00:00 2001 From: rjingar Date: Wed, 22 Jun 2016 11:17:41 -0700 Subject: [PATCH 117/124] Refactored out constants to include from header file --- realsense_camera/CMakeLists.txt | 21 ++++++ .../{src => include}/base_nodelet.h | 31 +------- realsense_camera/include/constants.h | 72 +++++++++++++++++++ .../{src => include}/r200_nodelet.h | 5 -- realsense_camera/src/base_nodelet.cpp | 4 +- realsense_camera/src/r200_nodelet.cpp | 5 +- realsense_camera/test/camera_core.cpp | 18 ++--- realsense_camera/test/camera_core.h | 40 ++++------- 8 files changed, 122 insertions(+), 74 deletions(-) rename realsense_camera/{src => include}/base_nodelet.h (80%) create mode 100644 realsense_camera/include/constants.h rename realsense_camera/{src => include}/r200_nodelet.h (91%) diff --git a/realsense_camera/CMakeLists.txt b/realsense_camera/CMakeLists.txt index 2a14aee2a7..c748806a6d 100644 --- a/realsense_camera/CMakeLists.txt +++ b/realsense_camera/CMakeLists.txt @@ -7,6 +7,7 @@ set(CMAKE_EXPORT_COMPILE_COMMANDS 1) # View the makefile commands during build #set(CMAKE_VERBOSE_MAKEFILE on) +# Set compile flags set(CMAKE_CXX_FLAGS "-fPIE -fPIC -std=c++11 -O2 -D_FORTIFY_SOURCE=2 -fstack-protector -Wformat -Wformat-security -Wall ${CMAKE_CXX_FLAGS}") # Flags executables set(CMAKE_EXE_LINKER_FLAGS "-pie -z noexecstack -z relro -z now") @@ -43,7 +44,22 @@ generate_dynamic_reconfigure_options( cfg/r200_params.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 +) + +# Specify additional locations of header files include_directories( + include ${catkin_INCLUDE_DIRS} ) @@ -73,6 +89,11 @@ install(TARGETS ${PROJECT_NAME}_nodelet LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} ) +# Install header files +install(DIRECTORY include/ + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/include +) + # Install launch files install(DIRECTORY launch/ DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch diff --git a/realsense_camera/src/base_nodelet.h b/realsense_camera/include/base_nodelet.h similarity index 80% rename from realsense_camera/src/base_nodelet.h rename to realsense_camera/include/base_nodelet.h index c43d905858..972801656a 100644 --- a/realsense_camera/src/base_nodelet.h +++ b/realsense_camera/include/base_nodelet.h @@ -62,6 +62,7 @@ #include #include #include +#include "constants.h" namespace realsense_camera { @@ -77,35 +78,6 @@ namespace realsense_camera virtual bool getCameraOptionValues(realsense_camera::cameraConfiguration::Request & req, realsense_camera::cameraConfiguration::Response & res); protected: - // Default Constants. - const int MAX_Z = 8; // in meters - const std::string DEFAULT_MODE = "preset"; - const int DEPTH_HEIGHT = 360; - const int DEPTH_WIDTH = 480; - const int COLOR_HEIGHT = 480; - const int COLOR_WIDTH = 640; - const int DEPTH_FPS = 60; - const int COLOR_FPS = 60; - const bool ENABLE_DEPTH = true; - const bool ENABLE_COLOR = true; - const bool ENABLE_PC = true; - const bool ENABLE_TF = true; - const rs_format DEPTH_FORMAT = RS_FORMAT_Z16; - const rs_format COLOR_FORMAT = RS_FORMAT_RGB8; - const rs_format IR1_FORMAT = RS_FORMAT_Y8; - const std::string DEFAULT_BASE_FRAME_ID = "camera_link"; - const std::string DEFAULT_DEPTH_FRAME_ID = "camera_depth_frame"; - const std::string DEFAULT_COLOR_FRAME_ID = "camera_rgb_frame"; - const std::string DEFAULT_DEPTH_OPTICAL_FRAME_ID = "camera_depth_optical_frame"; - const std::string DEFAULT_COLOR_OPTICAL_FRAME_ID = "camera_rgb_optical_frame"; - const std::string DEFAULT_IR_FRAME_ID = "camera_infrared_frame"; - const char *DEPTH_TOPIC = "camera/depth/image_raw"; - const char *COLOR_TOPIC = "camera/color/image_raw"; - const char *IR1_TOPIC = "camera/infrared1/image_raw"; - const char *PC_TOPIC = "camera/depth/points"; - const char *SETTINGS_SERVICE = "camera/get_settings"; - - const static int STREAM_COUNT = 4; // Member Variables. boost::shared_ptr stream_thread_; @@ -140,6 +112,7 @@ namespace realsense_camera std::string nodelet_name_; const uint16_t *image_depth16_; int num_streams_ = 3; + int max_z_ = -1; cv::Mat image_[STREAM_COUNT]; diff --git a/realsense_camera/include/constants.h b/realsense_camera/include/constants.h new file mode 100644 index 0000000000..abdb6452b3 --- /dev/null +++ b/realsense_camera/include/constants.h @@ -0,0 +1,72 @@ +/****************************************************************************** + Copyright (c) 2016, Intel Corporation + All rights reserved. + + Redistribution and use in source and binary forms, with or without + modification, are permitted provided that the following conditions are met: + + 1. Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + + 2. Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + + 3. Neither the name of the copyright holder nor the names of its contributors + may be used to endorse or promote products derived from this software without + specific prior written permission. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" + AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE + IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE + FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL + DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR + SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER + CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, + OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE + OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + *******************************************************************************/ + +#pragma once +#ifndef NODELET_CONSTANTS +#define NODELET_CONSTANTS + +namespace realsense_camera +{ + // Default Constants. + const int STREAM_COUNT = 4; + const int DEPTH_HEIGHT = 360; + const int DEPTH_WIDTH = 480; + const int COLOR_HEIGHT = 480; + const int COLOR_WIDTH = 640; + const int DEPTH_FPS = 60; + const int COLOR_FPS = 60; + const bool ENABLE_DEPTH = true; + const bool ENABLE_COLOR = true; + const bool ENABLE_PC = true; + const bool ENABLE_TF = true; + const rs_format DEPTH_FORMAT = RS_FORMAT_Z16; + const rs_format COLOR_FORMAT = RS_FORMAT_RGB8; + const rs_format IR_FORMAT = RS_FORMAT_Y8; + const std::string DEFAULT_MODE = "preset"; + const std::string DEFAULT_BASE_FRAME_ID = "camera_link"; + const std::string DEFAULT_DEPTH_FRAME_ID = "camera_depth_frame"; + const std::string DEFAULT_COLOR_FRAME_ID = "camera_rgb_frame"; + const std::string DEFAULT_DEPTH_OPTICAL_FRAME_ID = "camera_depth_optical_frame"; + const std::string DEFAULT_COLOR_OPTICAL_FRAME_ID = "camera_rgb_optical_frame"; + const std::string DEFAULT_IR_FRAME_ID = "camera_infrared_frame"; + const std::string DEFAULT_IR2_FRAME_ID = "camera_infrared2_frame"; + const std::string DEPTH_TOPIC = "camera/depth/image_raw"; + const std::string COLOR_TOPIC = "camera/color/image_raw"; + const std::string IR1_TOPIC = "camera/infrared1/image_raw"; + const std::string IR2_TOPIC = "camera/infrared2/image_raw"; + const std::string PC_TOPIC = "camera/depth/points"; + const std::string SETTINGS_SERVICE = "camera/get_settings"; + const double ROTATION_IDENTITY[] = {1, 0, 0, 0, 1, 0, 0, 0, 1}; + + // R200 Constants. + const int R200_STREAM_COUNT = 4; + const int R200_MAX_Z = 10; // in meters +} +#endif diff --git a/realsense_camera/src/r200_nodelet.h b/realsense_camera/include/r200_nodelet.h similarity index 91% rename from realsense_camera/src/r200_nodelet.h rename to realsense_camera/include/r200_nodelet.h index 64f5ae31d3..920054095a 100644 --- a/realsense_camera/src/r200_nodelet.h +++ b/realsense_camera/include/r200_nodelet.h @@ -47,11 +47,6 @@ namespace realsense_camera void onInit(); protected: - // R200 Constants. - const rs_format IR2_FORMAT = RS_FORMAT_Y8; - const std::string DEFAULT_IR2_FRAME_ID = "camera_infrared2_frame"; - const char *IR2_TOPIC = "camera/infrared2/image_raw"; - const int NUM_STREAMS_R200 = 4; // Member Variables. std::string ir2_frame_id_; diff --git a/realsense_camera/src/base_nodelet.cpp b/realsense_camera/src/base_nodelet.cpp index cd6c4ae7a2..a1b9a91016 100644 --- a/realsense_camera/src/base_nodelet.cpp +++ b/realsense_camera/src/base_nodelet.cpp @@ -174,7 +174,7 @@ namespace realsense_camera if (mode_.compare ("manual") == 0) { ROS_INFO_STREAM(nodelet_name_ << " - Enabling Infrared stream: manual mode"); - rs_enable_stream(rs_device_, RS_STREAM_INFRARED, depth_width_, depth_height_, IR1_FORMAT, depth_fps_, &rs_error_); + rs_enable_stream(rs_device_, RS_STREAM_INFRARED, depth_width_, depth_height_, IR_FORMAT, depth_fps_, &rs_error_); checkError(); } else @@ -686,7 +686,7 @@ namespace realsense_camera { (float) x, (float) y}; rs_deproject_pixel_to_point(depth_point, &z_intrinsic, depth_pixel, scaled_depth); - if (depth_point[2] <= 0 || depth_point[2] > MAX_Z) + if (depth_point[2] <= 0 || depth_point[2] > max_z_) { depth_point[0] = 0; depth_point[1] = 0; diff --git a/realsense_camera/src/r200_nodelet.cpp b/realsense_camera/src/r200_nodelet.cpp index 50f45f92f5..b65e9f8f9b 100644 --- a/realsense_camera/src/r200_nodelet.cpp +++ b/realsense_camera/src/r200_nodelet.cpp @@ -45,7 +45,8 @@ namespace realsense_camera { // set member vars used in base class nodelet_name_ = getName(); - num_streams_ = NUM_STREAMS_R200; + num_streams_ = R200_STREAM_COUNT; + max_z_ = R200_MAX_Z; nh_ = getNodeHandle(); pnh_ = getPrivateNodeHandle(); @@ -90,7 +91,7 @@ namespace realsense_camera if (mode_.compare ("manual") == 0) { ROS_INFO_STREAM(nodelet_name_ << " - Enabling Infrared2 stream: manual mode"); - rs_enable_stream(rs_device_, RS_STREAM_INFRARED2, depth_width_, depth_height_, IR2_FORMAT, depth_fps_, &rs_error_); + rs_enable_stream(rs_device_, RS_STREAM_INFRARED2, depth_width_, depth_height_, IR_FORMAT, depth_fps_, &rs_error_); checkError(); } else diff --git a/realsense_camera/test/camera_core.cpp b/realsense_camera/test/camera_core.cpp index 138e01f55c..ec31796d81 100644 --- a/realsense_camera/test/camera_core.cpp +++ b/realsense_camera/test/camera_core.cpp @@ -28,10 +28,10 @@ OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. *******************************************************************************/ #include "gtest/gtest.h" - #include "camera_core.h" -using namespace std; +using namespace std; +using namespace realsense_camera; void getMsgInfo(rs_stream stream, const sensor_msgs::ImageConstPtr &msg) { @@ -126,7 +126,7 @@ void imageDepthCallback(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs int depth_count = 0; for (unsigned int i = 0; i < msg->height * msg->width; ++i) { - if ((0 < *image_data) && (*image_data <= R200_DEPTH_MAX)) + if ((0 < *image_data) && (*image_data <= g_max_z)) { depth_total += *image_data; depth_count++; @@ -156,7 +156,7 @@ void pcCallback(const sensor_msgs::PointCloud2ConstPtr pc) { pcl::PointXYZRGB point = pointcloud.points[i]; float pc_depth = (float) std::ceil(point.z); - if ((0 < pc_depth) && (pc_depth <= R200_DEPTH_MAX)) + if ((0 < pc_depth) && (pc_depth <= g_max_z)) { pc_depth_total += pc_depth; pc_depth_count++; @@ -507,10 +507,10 @@ TEST(RealsenseTests, testTransforms) // make sure all transforms are being broadcast as expected tf::TransformListener tf_listener; - EXPECT_TRUE(tf_listener.waitForTransform (DEPTH_DEF_FRAME, BASE_DEF_FRAME, ros::Time(0), ros::Duration(3.0))); - EXPECT_TRUE(tf_listener.waitForTransform (DEPTH_OPTICAL_DEF_FRAME, DEPTH_DEF_FRAME, ros::Time(0), ros::Duration(3.0))); - EXPECT_TRUE(tf_listener.waitForTransform (COLOR_DEF_FRAME, BASE_DEF_FRAME, ros::Time(0), ros::Duration(3.0))); - EXPECT_TRUE(tf_listener.waitForTransform (COLOR_OPTICAL_DEF_FRAME, COLOR_DEF_FRAME, ros::Time(0), ros::Duration(3.0))); + EXPECT_TRUE(tf_listener.waitForTransform (DEFAULT_DEPTH_FRAME_ID, DEFAULT_BASE_FRAME_ID, ros::Time(0), ros::Duration(3.0))); + EXPECT_TRUE(tf_listener.waitForTransform (DEFAULT_DEPTH_OPTICAL_FRAME_ID, DEFAULT_DEPTH_FRAME_ID, ros::Time(0), ros::Duration(3.0))); + EXPECT_TRUE(tf_listener.waitForTransform (DEFAULT_COLOR_FRAME_ID, DEFAULT_BASE_FRAME_ID, ros::Time(0), ros::Duration(3.0))); + EXPECT_TRUE(tf_listener.waitForTransform (DEFAULT_COLOR_OPTICAL_FRAME_ID, DEFAULT_COLOR_FRAME_ID, ros::Time(0), ros::Duration(3.0))); } TEST(RealsenseTests, testCameraOptions) @@ -635,7 +635,7 @@ int main(int argc, char **argv) try g_camera_subscriber[0] = it.subscribeCamera(DEPTH_TOPIC, 1, imageDepthCallback, 0); g_camera_subscriber[1] = it.subscribeCamera(COLOR_TOPIC, 1, imageColorCallback, 0); g_camera_subscriber[2] = it.subscribeCamera(IR1_TOPIC, 1, imageInfrared1Callback, 0); - if (g_camera.find(R200) != std::string::npos) + if (g_camera.find("R200") != std::string::npos) { g_camera_subscriber[3] = it.subscribeCamera(IR2_TOPIC, 1, imageInfrared2Callback, 0); } diff --git a/realsense_camera/test/camera_core.h b/realsense_camera/test/camera_core.h index cbaeaed122..a1931c1c42 100644 --- a/realsense_camera/test/camera_core.h +++ b/realsense_camera/test/camera_core.h @@ -52,24 +52,9 @@ #include #include #include +#include "constants.h" -#define R200_STREAMS_COUNT 4 - -const char *DEPTH_TOPIC = "camera/depth/image_raw"; -const char *COLOR_TOPIC = "camera/color/image_raw"; -const char *IR1_TOPIC = "camera/infrared1/image_raw"; -const char *IR2_TOPIC = "camera/infrared2/image_raw"; -const char *PC_TOPIC = "camera/depth/points"; -const char *SETTINGS_SERVICE = "camera/get_settings"; -const char *R200 = "R200"; -const int R200_DEPTH_MAX = 10000; - -const char *BASE_DEF_FRAME = "camera_link"; -const char *DEPTH_DEF_FRAME = "camera_depth_frame"; -const char *COLOR_DEF_FRAME = "camera_rgb_frame"; -const char *DEPTH_OPTICAL_DEF_FRAME = "camera_depth_optical_frame"; -const char *COLOR_OPTICAL_DEF_FRAME = "camera_rgb_optical_frame"; -const double ROTATION_IDENTITY[] = {1, 0, 0, 0, 1, 0, 0, 0, 1}; +using namespace realsense_camera; //utest commandline args int g_color_height_exp = 0; @@ -90,10 +75,11 @@ std::string g_color_encoding_exp; // Expected color encoding. std::string g_infrared1_encoding_exp; // Expected infrared1 encoding. std::string g_infrared2_encoding_exp; // Expected infrared2 encoding. -image_transport::CameraSubscriber g_camera_subscriber[R200_STREAMS_COUNT]; +image_transport::CameraSubscriber g_camera_subscriber[STREAM_COUNT]; ros::Subscriber g_sub_pc; std::map g_config_args; +int g_max_z = R200_MAX_Z * 1000; // Converting meter to mm. bool g_depth_recv = false; bool g_color_recv = false; @@ -107,20 +93,20 @@ float g_infrared1_avg = 0; float g_infrared2_avg = 0; float g_pc_depth_avg = 0; -int g_height_recv[R200_STREAMS_COUNT] = {0}; -int g_width_recv[R200_STREAMS_COUNT] = {0}; -uint32_t g_step_recv[R200_STREAMS_COUNT] = {0}; // Received stream step. +int g_height_recv[STREAM_COUNT] = {0}; +int g_width_recv[STREAM_COUNT] = {0}; +uint32_t g_step_recv[STREAM_COUNT] = {0}; // Received stream step. -std::string g_encoding_recv[R200_STREAMS_COUNT]; // Expected stream encoding. +std::string g_encoding_recv[STREAM_COUNT]; // Expected stream encoding. -int g_caminfo_height_recv[R200_STREAMS_COUNT] = {0}; -int g_caminfo_width_recv[R200_STREAMS_COUNT] = {0}; +int g_caminfo_height_recv[STREAM_COUNT] = {0}; +int g_caminfo_width_recv[STREAM_COUNT] = {0}; float g_color_caminfo_D_recv[5] = {0}; -double g_caminfo_rotation_recv[R200_STREAMS_COUNT][9] = {0}; -double g_caminfo_projection_recv[R200_STREAMS_COUNT][12] = {0}; +double g_caminfo_rotation_recv[STREAM_COUNT][9] = {0}; +double g_caminfo_projection_recv[STREAM_COUNT][12] = {0}; -std::string g_dmodel_recv[R200_STREAMS_COUNT]; +std::string g_dmodel_recv[STREAM_COUNT]; std::string g_camera = "R200"; realsense_camera::cameraConfiguration g_srv; From df8a081ddba951fda1de33584bf21d2a0ec49564 Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Fri, 24 Jun 2016 11:24:39 -0700 Subject: [PATCH 118/124] Refactored functions for enabling and disabling streams Refactored the infrared terms to be consistent Updated README with the correct API documentation --- realsense_camera/README.md | 28 +++-- realsense_camera/include/base_nodelet.h | 10 +- realsense_camera/include/constants.h | 9 +- realsense_camera/include/r200_nodelet.h | 6 +- ...realsense_r200_multiple_cameras.launch.xml | 8 +- .../realsense_r200_nodelet.launch.xml | 8 +- .../rviz/realsenseRvizConfiguration1.rviz | 4 +- realsense_camera/src/base_nodelet.cpp | 118 ++++-------------- realsense_camera/src/r200_nodelet.cpp | 48 ++----- realsense_camera/test/camera_core.cpp | 2 +- 10 files changed, 73 insertions(+), 168 deletions(-) diff --git a/realsense_camera/README.md b/realsense_camera/README.md index 8b22f4b438..bf3d96c0a8 100644 --- a/realsense_camera/README.md +++ b/realsense_camera/README.md @@ -53,16 +53,16 @@ Depth camera camera/depth/points (sensor_msgs/PointCloud2) Registered XYZRGB point cloud. -Infrared1 camera +IR camera - camera/infrared1/image_raw (sensor_msgs/Image) - camera/infrared1/camera_info + camera/ir/image_raw (sensor_msgs/Image) + camera/ir/camera_info Calibration data -Infrared2 camera +IR2 camera - camera/infrared2/image_raw (sensor_msgs/Image) - camera/infrared2/camera_info + camera/ir2/image_raw (sensor_msgs/Image) + camera/ir2/camera_info Calibration data ####Services @@ -116,9 +116,9 @@ Infrared2 camera Specify the depth optical frame id of the camera. color_optical_frame_id (string, default: camera_rgb_optical_frame) Specify the color optical frame id of the camera. - ir_frame_id (string, default: camera_infrared_frame) + ir_frame_id (string, default: camera_ir_frame) Specify the IR frame id of the camera. - ir2_frame_id (string, default: camera_infrared2_frame) + ir2_frame_id (string, default: camera_ir2_frame) Specify the IR2 frame id of the camera. camera (string, default: "R200") Specify the camera name. @@ -142,8 +142,8 @@ Infrared2 camera Stream parameters: enable_depth (bool, default: true) - Specify if to enable or not the depth and infrared camera. - Note: Infrared streams will be enabled or disabled along with depth stream. + Specify if to enable or not the depth and infrared camera(s). + Note: Infrared stream(s) will be enabled or disabled along with depth stream. Camera parameters: Following are the parameters that can be set dynamically as well as statically in the R200 camera. @@ -191,7 +191,7 @@ If you would like to create or use your own launch files, the nodelet name for t View using RVIZ: -For color, infrared1 and infrared2 streams, you can open RVIZ and load the published topics. +For color and infrared stream(s), you can open RVIZ and load the published topics. You can also open RVIZ and load the provided RVIZ configuration file: realsenseRvizConfiguration1.rviz. ``` @@ -266,7 +266,9 @@ Sample test files are available in "realsense_camera/test" directory * realsense_r200_resolution.test ###Developer API: -Refer to the function definitions in [realsense_camera_nodelet.h](src/realsense_camera_nodelet.h) +Refer to the following: +* [base_nodelet.h](include/base_nodelet.h) +* [r200_nodelet.h](include/r200_nodelet.h) ###Limitations: * Currently, the camera nodelet has been tested to work only for R200 cameras. @@ -274,7 +276,7 @@ Refer to the function definitions in [realsense_camera_nodelet.h](src/realsense_ * Currently, the camera nodelet only supports the following formats: * Color stream: RGB8 * Depth stream: Z16 - * Infrared stream: Y8 + * Infrared stream(s): Y8 * Generating a Depth Registered Point Cloud is very memory intensive. The topic /camera/depth_registered/points, generated by launch file diff --git a/realsense_camera/include/base_nodelet.h b/realsense_camera/include/base_nodelet.h index 972801656a..f9c3b693f9 100644 --- a/realsense_camera/include/base_nodelet.h +++ b/realsense_camera/include/base_nodelet.h @@ -149,15 +149,11 @@ namespace realsense_camera std::vector camera_options_; // Member Functions. - virtual void enableStreams(); - virtual void enableColorStream(); - virtual void enableDepthStream(); - virtual void disableDepthStream(); - virtual void enableInfraredStream(); - virtual void disableInfraredStream(); + virtual void enableStream(rs_stream stream_index, int width, int height, rs_format format, int fps); + virtual void prepareStreamCalibData(rs_stream stream_index); + virtual void disableStream(rs_stream stream_index); virtual void fillStreamEncoding(); virtual void setStreamOptions(); - virtual void prepareStreamCalibData(rs_stream calib_data); virtual void prepareStreamData(rs_stream rs_strm); virtual void getCameraOptions(); diff --git a/realsense_camera/include/constants.h b/realsense_camera/include/constants.h index abdb6452b3..9ba4feeb65 100644 --- a/realsense_camera/include/constants.h +++ b/realsense_camera/include/constants.h @@ -55,14 +55,15 @@ namespace realsense_camera const std::string DEFAULT_COLOR_FRAME_ID = "camera_rgb_frame"; const std::string DEFAULT_DEPTH_OPTICAL_FRAME_ID = "camera_depth_optical_frame"; const std::string DEFAULT_COLOR_OPTICAL_FRAME_ID = "camera_rgb_optical_frame"; - const std::string DEFAULT_IR_FRAME_ID = "camera_infrared_frame"; - const std::string DEFAULT_IR2_FRAME_ID = "camera_infrared2_frame"; + const std::string DEFAULT_IR_FRAME_ID = "camera_ir_frame"; + const std::string DEFAULT_IR2_FRAME_ID = "camera_ir2_frame"; const std::string DEPTH_TOPIC = "camera/depth/image_raw"; const std::string COLOR_TOPIC = "camera/color/image_raw"; - const std::string IR1_TOPIC = "camera/infrared1/image_raw"; - const std::string IR2_TOPIC = "camera/infrared2/image_raw"; + const std::string IR_TOPIC = "camera/ir/image_raw"; + const std::string IR2_TOPIC = "camera/ir2/image_raw"; const std::string PC_TOPIC = "camera/depth/points"; const std::string SETTINGS_SERVICE = "camera/get_settings"; + const std::string STREAM_DESC[STREAM_COUNT] = {"Depth", "Color", "IR", "IR2"}; const double ROTATION_IDENTITY[] = {1, 0, 0, 0, 1, 0, 0, 0, 1}; // R200 Constants. diff --git a/realsense_camera/include/r200_nodelet.h b/realsense_camera/include/r200_nodelet.h index 920054095a..77d7665162 100644 --- a/realsense_camera/include/r200_nodelet.h +++ b/realsense_camera/include/r200_nodelet.h @@ -53,10 +53,8 @@ namespace realsense_camera boost::shared_ptr> dynamic_reconf_server_; // Member Functions. - void enableDepthStream(); - void disableDepthStream(); - void enableInfrared2Stream(); - void disableInfrared2Stream(); + void enableStream(rs_stream stream_index, int width, int height, rs_format format, int fps); + void disableStream(rs_stream stream_index); void setStreamOptions(); void fillStreamEncoding(); void allocateResources(); diff --git a/realsense_camera/launch/includes/realsense_r200_multiple_cameras.launch.xml b/realsense_camera/launch/includes/realsense_r200_multiple_cameras.launch.xml index aec4b6c0bf..33f3f702aa 100644 --- a/realsense_camera/launch/includes/realsense_r200_multiple_cameras.launch.xml +++ b/realsense_camera/launch/includes/realsense_r200_multiple_cameras.launch.xml @@ -19,13 +19,13 @@ - - + + - - + + diff --git a/realsense_camera/launch/includes/realsense_r200_nodelet.launch.xml b/realsense_camera/launch/includes/realsense_r200_nodelet.launch.xml index 608b4bc538..804a666b77 100644 --- a/realsense_camera/launch/includes/realsense_r200_nodelet.launch.xml +++ b/realsense_camera/launch/includes/realsense_r200_nodelet.launch.xml @@ -59,12 +59,12 @@ - - + + - - + + diff --git a/realsense_camera/rviz/realsenseRvizConfiguration1.rviz b/realsense_camera/rviz/realsenseRvizConfiguration1.rviz index 670e9969bd..33f0cdad8a 100644 --- a/realsense_camera/rviz/realsenseRvizConfiguration1.rviz +++ b/realsense_camera/rviz/realsenseRvizConfiguration1.rviz @@ -80,7 +80,7 @@ Visualization Manager: Value: true - Class: rviz/Image Enabled: true - Image Topic: /camera/infrared1/image_raw + Image Topic: /camera/ir/image_raw Max Value: 1 Median window: 5 Min Value: 0 @@ -102,7 +102,7 @@ Visualization Manager: Value: true - Class: rviz/Image Enabled: false - Image Topic: /camera/infrared2/image_raw + Image Topic: /camera/ir2/image_raw Max Value: 1 Median window: 5 Min Value: 0 diff --git a/realsense_camera/src/base_nodelet.cpp b/realsense_camera/src/base_nodelet.cpp index a1b9a91016..0f23620fb1 100644 --- a/realsense_camera/src/base_nodelet.cpp +++ b/realsense_camera/src/base_nodelet.cpp @@ -93,7 +93,7 @@ namespace realsense_camera image_transport::ImageTransport it (nh_); camera_publisher_[RS_STREAM_COLOR] = it.advertiseCamera(COLOR_TOPIC, 1); camera_publisher_[RS_STREAM_DEPTH] = it.advertiseCamera(DEPTH_TOPIC, 1); - camera_publisher_[RS_STREAM_INFRARED] = it.advertiseCamera(IR1_TOPIC, 1); + camera_publisher_[RS_STREAM_INFRARED] = it.advertiseCamera(IR_TOPIC, 1); pointcloud_publisher_ = nh_.advertise(PC_TOPIC, 1); @@ -120,92 +120,32 @@ namespace realsense_camera /* *Protected Methods. */ - void BaseNodelet::enableColorStream() + void BaseNodelet::enableStream(rs_stream stream_index, int width, int height, rs_format format, int fps) { // Enable streams. - if (mode_.compare ("manual") == 0) + if (mode_.compare("manual") == 0) { - ROS_INFO_STREAM(nodelet_name_ << " - Enabling Color stream: manual mode"); - rs_enable_stream(rs_device_, RS_STREAM_COLOR, color_width_, color_height_, COLOR_FORMAT, color_fps_, &rs_error_); + ROS_INFO_STREAM(nodelet_name_ << " - Enabling " << STREAM_DESC[stream_index] << " stream: manual mode"); + rs_enable_stream(rs_device_, stream_index, width, height, format, fps, &rs_error_); checkError(); } else { - ROS_INFO_STREAM(nodelet_name_ << " - Enabling Color stream: preset mode"); - rs_enable_stream_preset(rs_device_, RS_STREAM_COLOR, RS_PRESET_BEST_QUALITY, &rs_error_); + ROS_INFO_STREAM(nodelet_name_ << " - Enabling " << STREAM_DESC[stream_index] << " stream: preset mode"); + rs_enable_stream_preset(rs_device_, stream_index, RS_PRESET_BEST_QUALITY, &rs_error_); checkError(); } - uint32_t stream_index = (uint32_t) RS_STREAM_COLOR; if (camera_info_[stream_index] == NULL) { - prepareStreamCalibData (RS_STREAM_COLOR); + prepareStreamCalibData(stream_index); } } - void BaseNodelet::enableDepthStream() + void BaseNodelet::disableStream(rs_stream stream_index) { - // Enable streams. - if (mode_.compare ("manual") == 0) - { - ROS_INFO_STREAM(nodelet_name_ << " - Enabling Depth stream: manual mode"); - rs_enable_stream(rs_device_, RS_STREAM_DEPTH, depth_width_, depth_height_, DEPTH_FORMAT, depth_fps_, &rs_error_); - checkError(); - } - else - { - ROS_INFO_STREAM(nodelet_name_ << " - Enabling Depth stream: preset mode"); - rs_enable_stream_preset(rs_device_, RS_STREAM_DEPTH, RS_PRESET_BEST_QUALITY, &rs_error_); - checkError(); - } - - uint32_t stream_index = (uint32_t) RS_STREAM_DEPTH; - if (camera_info_[stream_index] == NULL) - { - prepareStreamCalibData (RS_STREAM_DEPTH); - } - // must enable IR stream also - enableInfraredStream(); - } - - void BaseNodelet::enableInfraredStream() - { - // Enable streams. - if (mode_.compare ("manual") == 0) - { - ROS_INFO_STREAM(nodelet_name_ << " - Enabling Infrared stream: manual mode"); - rs_enable_stream(rs_device_, RS_STREAM_INFRARED, depth_width_, depth_height_, IR_FORMAT, depth_fps_, &rs_error_); - checkError(); - } - else - { - ROS_INFO_STREAM(nodelet_name_ << " - Enabling Infrared stream: preset mode"); - rs_enable_stream_preset(rs_device_, RS_STREAM_INFRARED, RS_PRESET_BEST_QUALITY, &rs_error_); - checkError(); - } - - uint32_t stream_index = (uint32_t) RS_STREAM_INFRARED; - if (camera_info_[stream_index] == NULL) - { - prepareStreamCalibData (RS_STREAM_INFRARED); - } - } - - void BaseNodelet::disableDepthStream() - { - // disable depth stream - ROS_INFO_STREAM(nodelet_name_ << " - Disabling Depth stream"); - rs_disable_stream(rs_device_, RS_STREAM_DEPTH, &rs_error_); - checkError(); - - // disable IR stream - disableInfraredStream(); - } - - void BaseNodelet::disableInfraredStream() - { - ROS_INFO_STREAM(nodelet_name_ << " - Disabling Infrared stream"); - rs_disable_stream(rs_device_, RS_STREAM_INFRARED, &rs_error_); + ROS_INFO_STREAM(nodelet_name_ << " - Disabling " << STREAM_DESC[stream_index] << " stream"); + rs_disable_stream(rs_device_, stream_index, &rs_error_); checkError(); } @@ -223,19 +163,6 @@ namespace realsense_camera } } - void BaseNodelet::enableStreams() - { - // Enable streams. - if (enable_color_ == true) - { - enableColorStream(); - } - if (enable_depth_ == true) - { - enableDepthStream(); - } - } - bool BaseNodelet::connectToCamera() { rs_context_ = rs_create_context(RS_API_VERSION, &rs_error_); @@ -301,7 +228,15 @@ namespace realsense_camera checkError(); // Enable streams. - enableStreams(); + if (enable_color_ == true) + { + enableStream(RS_STREAM_COLOR, color_width_, color_height_, COLOR_FORMAT, color_fps_); + } + if (enable_depth_ == true) + { + enableStream(RS_STREAM_DEPTH, depth_width_, depth_height_, DEPTH_FORMAT, depth_fps_); + enableStream(RS_STREAM_INFRARED, depth_width_, depth_height_, IR_FORMAT, depth_fps_); + } getCameraOptions(); setStaticCameraOptions(); @@ -374,11 +309,10 @@ namespace realsense_camera /* * Prepare camera_info for each enabled stream. */ - void BaseNodelet::prepareStreamCalibData(rs_stream rs_strm) + void BaseNodelet::prepareStreamCalibData(rs_stream stream_index) { - uint32_t stream_index = (uint32_t) rs_strm; rs_intrinsics intrinsic; - rs_get_stream_intrinsics(rs_device_, rs_strm, &intrinsic, &rs_error_); + rs_get_stream_intrinsics(rs_device_, stream_index, &intrinsic, &rs_error_); checkError(); camera_info_[stream_index] = new sensor_msgs::CameraInfo(); @@ -532,8 +466,9 @@ namespace realsense_camera checkError(); } - // disable depth stream - disableDepthStream(); + // disable Depth and IR stream + disableStream(RS_STREAM_DEPTH); + disableStream(RS_STREAM_INFRARED); if (rs_is_device_streaming(rs_device_, 0) == 0) { @@ -552,7 +487,8 @@ namespace realsense_camera checkError(); } - enableDepthStream(); + enableStream(RS_STREAM_DEPTH, depth_width_, depth_height_, DEPTH_FORMAT, depth_fps_); + enableStream(RS_STREAM_INFRARED, depth_width_, depth_height_, IR_FORMAT, depth_fps_); if (rs_is_device_streaming(rs_device_, 0) == 0) { diff --git a/realsense_camera/src/r200_nodelet.cpp b/realsense_camera/src/r200_nodelet.cpp index b65e9f8f9b..92e94bfec2 100644 --- a/realsense_camera/src/r200_nodelet.cpp +++ b/realsense_camera/src/r200_nodelet.cpp @@ -69,50 +69,22 @@ namespace realsense_camera /* *Protected Methods. */ - void R200Nodelet::enableDepthStream() + void R200Nodelet::enableStream(rs_stream stream_index, int width, int height, rs_format format, int fps) { - // call the base class method first - BaseNodelet::enableDepthStream(); - // enable IR2 stream - enableInfrared2Stream(); - } - - void R200Nodelet::disableDepthStream() - { - // call the base class method first - BaseNodelet::disableDepthStream(); - // disable IR2 stream - disableInfrared2Stream(); - } - - void R200Nodelet::enableInfrared2Stream() - { - // Enable streams. - if (mode_.compare ("manual") == 0) - { - ROS_INFO_STREAM(nodelet_name_ << " - Enabling Infrared2 stream: manual mode"); - rs_enable_stream(rs_device_, RS_STREAM_INFRARED2, depth_width_, depth_height_, IR_FORMAT, depth_fps_, &rs_error_); - checkError(); - } - else + BaseNodelet::enableStream(stream_index, width, height, format, fps); + if (stream_index == RS_STREAM_INFRARED) { - ROS_INFO_STREAM(nodelet_name_ << " - Enabling Infrared2 stream: preset mode"); - rs_enable_stream_preset(rs_device_, RS_STREAM_INFRARED2, RS_PRESET_BEST_QUALITY, &rs_error_); - checkError(); - } - - uint32_t stream_index = (uint32_t) RS_STREAM_INFRARED2; - if (camera_info_[stream_index] == NULL) - { - prepareStreamCalibData (RS_STREAM_INFRARED2); + enableStream(RS_STREAM_INFRARED2, depth_width_, depth_height_, IR_FORMAT, depth_fps_); } } - void R200Nodelet::disableInfrared2Stream() + void R200Nodelet::disableStream(rs_stream stream_index) { - ROS_INFO_STREAM(nodelet_name_ << " - Disabling Infrared2 stream"); - rs_disable_stream(rs_device_, RS_STREAM_INFRARED2, &rs_error_); - checkError(); + BaseNodelet::disableStream(stream_index); + if (stream_index == RS_STREAM_INFRARED) + { + disableStream(RS_STREAM_INFRARED2); + } } void R200Nodelet::configCallback(realsense_camera::r200_paramsConfig &config, uint32_t level) diff --git a/realsense_camera/test/camera_core.cpp b/realsense_camera/test/camera_core.cpp index ec31796d81..a7a4f2ed58 100644 --- a/realsense_camera/test/camera_core.cpp +++ b/realsense_camera/test/camera_core.cpp @@ -634,7 +634,7 @@ int main(int argc, char **argv) try image_transport::ImageTransport it(nh); g_camera_subscriber[0] = it.subscribeCamera(DEPTH_TOPIC, 1, imageDepthCallback, 0); g_camera_subscriber[1] = it.subscribeCamera(COLOR_TOPIC, 1, imageColorCallback, 0); - g_camera_subscriber[2] = it.subscribeCamera(IR1_TOPIC, 1, imageInfrared1Callback, 0); + g_camera_subscriber[2] = it.subscribeCamera(IR_TOPIC, 1, imageInfrared1Callback, 0); if (g_camera.find("R200") != std::string::npos) { g_camera_subscriber[3] = it.subscribeCamera(IR2_TOPIC, 1, imageInfrared2Callback, 0); From 48e437e78443388a882e54e4b03ed694ffe1101f Mon Sep 17 00:00:00 2001 From: rjingar Date: Sun, 26 Jun 2016 12:48:56 -0700 Subject: [PATCH 119/124] Refactored code to reduce reliance on base class member variables --- realsense_camera/include/base_nodelet.h | 73 +++------ realsense_camera/include/r200_nodelet.h | 7 +- realsense_camera/src/base_nodelet.cpp | 208 +++++++++++++----------- realsense_camera/src/r200_nodelet.cpp | 31 ++-- 4 files changed, 153 insertions(+), 166 deletions(-) diff --git a/realsense_camera/include/base_nodelet.h b/realsense_camera/include/base_nodelet.h index f9c3b693f9..0ec7333f21 100644 --- a/realsense_camera/include/base_nodelet.h +++ b/realsense_camera/include/base_nodelet.h @@ -80,66 +80,38 @@ namespace realsense_camera protected: // Member Variables. - boost::shared_ptr stream_thread_; - boost::shared_ptr transform_thread_; + ros::NodeHandle nh_; + ros::NodeHandle pnh_; rs_error *rs_error_ = 0; rs_context *rs_context_; rs_device *rs_device_; - std::vector rs_detected_devices_; - - int num_of_cameras_; - std::string serial_no_; - std::string usb_port_id_; - int color_height_; - int color_width_; - int depth_height_; - int depth_width_; - int depth_fps_; - int color_fps_; + int height_[STREAM_COUNT]; + int width_[STREAM_COUNT]; + int fps_[STREAM_COUNT]; + int stream_step_[STREAM_COUNT]; + int stream_ts_[STREAM_COUNT]; + int num_streams_ = 3; + int max_z_ = -1; bool is_device_started_; bool enable_color_; bool enable_depth_; bool enable_pointcloud_; bool enable_tf_; - std::string base_frame_id_; - std::string depth_frame_id_; - std::string color_frame_id_; - std::string depth_optical_frame_id_; - std::string color_optical_frame_id_; - std::string ir_frame_id_; - std::string camera_; + + std::string frame_id_[STREAM_COUNT]; + std::string stream_encoding_[STREAM_COUNT]; std::string nodelet_name_; const uint16_t *image_depth16_; - int num_streams_ = 3; - int max_z_ = -1; cv::Mat image_[STREAM_COUNT]; - rs_option edge_options_[4] = { - RS_OPTION_R200_AUTO_EXPOSURE_LEFT_EDGE, - RS_OPTION_R200_AUTO_EXPOSURE_TOP_EDGE, - RS_OPTION_R200_AUTO_EXPOSURE_RIGHT_EDGE, - RS_OPTION_R200_AUTO_EXPOSURE_BOTTOM_EDGE - }; - double edge_values_[4]; - - sensor_msgs::CameraInfoPtr camera_info_ptr_[STREAM_COUNT]; - sensor_msgs::CameraInfo * camera_info_[STREAM_COUNT]; image_transport::CameraPublisher camera_publisher_[STREAM_COUNT]; - - ros::Time time_stamp_; + sensor_msgs::CameraInfoPtr camera_info_ptr_[STREAM_COUNT]; ros::Publisher pointcloud_publisher_; - ros::ServiceServer get_options_service_; - ros::NodeHandle nh_; - ros::NodeHandle pnh_; - std::string frame_id_[STREAM_COUNT]; - std::string stream_encoding_[STREAM_COUNT]; - std::string mode_; - std::map config_; - int stream_step_[STREAM_COUNT]; - int stream_ts_[STREAM_COUNT]; + boost::shared_ptr stream_thread_; + boost::shared_ptr transform_thread_; struct CameraOptions { @@ -149,21 +121,20 @@ namespace realsense_camera std::vector camera_options_; // Member Functions. + virtual void listCameras(int num_of_camera); + virtual bool connectToCamera(); virtual void enableStream(rs_stream stream_index, int width, int height, rs_format format, int fps); - virtual void prepareStreamCalibData(rs_stream stream_index); virtual void disableStream(rs_stream stream_index); - virtual void fillStreamEncoding(); - virtual void setStreamOptions(); + virtual void prepareStreamCalibData(rs_stream stream_index); virtual void prepareStreamData(rs_stream rs_strm); - - virtual void getCameraOptions(); virtual void allocateResources(); - virtual void listCameras(); - virtual bool connectToCamera(); + virtual void fillStreamEncoding(); + virtual void setStreamOptions(); virtual void setStaticCameraOptions() { return; } // must be defined in derived class + virtual void getCameraOptions(); virtual void checkError(); - virtual void publishPointCloud(cv::Mat & image_rgb); + virtual void publishPointCloud(cv::Mat & image_rgb, ros::Time time_stamp); }; } #endif diff --git a/realsense_camera/include/r200_nodelet.h b/realsense_camera/include/r200_nodelet.h index 77d7665162..2871dd263a 100644 --- a/realsense_camera/include/r200_nodelet.h +++ b/realsense_camera/include/r200_nodelet.h @@ -49,7 +49,12 @@ namespace realsense_camera protected: // Member Variables. - std::string ir2_frame_id_; + rs_option edge_options_[4] = { + RS_OPTION_R200_AUTO_EXPOSURE_LEFT_EDGE, + RS_OPTION_R200_AUTO_EXPOSURE_TOP_EDGE, + RS_OPTION_R200_AUTO_EXPOSURE_RIGHT_EDGE, + RS_OPTION_R200_AUTO_EXPOSURE_BOTTOM_EDGE + }; boost::shared_ptr> dynamic_reconf_server_; // Member Functions. diff --git a/realsense_camera/src/base_nodelet.cpp b/realsense_camera/src/base_nodelet.cpp index 0f23620fb1..7d9df22df9 100644 --- a/realsense_camera/src/base_nodelet.cpp +++ b/realsense_camera/src/base_nodelet.cpp @@ -72,7 +72,7 @@ namespace realsense_camera for (int i = 0; i < num_streams_; ++i) { - camera_info_[i] = NULL; + camera_info_ptr_[i] = NULL; stream_ts_[i] = -1; } @@ -84,11 +84,6 @@ namespace realsense_camera ros::shutdown(); } - // Set up the topics. - frame_id_[RS_STREAM_DEPTH] = depth_optical_frame_id_; - frame_id_[RS_STREAM_COLOR] = color_optical_frame_id_; - frame_id_[RS_STREAM_INFRARED] = ir_frame_id_; - // Advertise the various topics and services. image_transport::ImageTransport it (nh_); camera_publisher_[RS_STREAM_COLOR] = it.advertiseCamera(COLOR_TOPIC, 1); @@ -97,7 +92,7 @@ namespace realsense_camera pointcloud_publisher_ = nh_.advertise(PC_TOPIC, 1); - get_options_service_ = nh_.advertiseService(SETTINGS_SERVICE, &BaseNodelet::getCameraOptionValues, this); + ros::ServiceServer get_options_service = nh_.advertiseService(SETTINGS_SERVICE, &BaseNodelet::getCameraOptionValues, this); // Poll for camera and connect if found while (!connectToCamera()) @@ -122,8 +117,11 @@ namespace realsense_camera */ void BaseNodelet::enableStream(rs_stream stream_index, int width, int height, rs_format format, int fps) { + std::string stream_mode; + pnh_.param("mode", stream_mode, DEFAULT_MODE); + // Enable streams. - if (mode_.compare("manual") == 0) + if (stream_mode.compare("manual") == 0) { ROS_INFO_STREAM(nodelet_name_ << " - Enabling " << STREAM_DESC[stream_index] << " stream: manual mode"); rs_enable_stream(rs_device_, stream_index, width, height, format, fps, &rs_error_); @@ -136,7 +134,7 @@ namespace realsense_camera checkError(); } - if (camera_info_[stream_index] == NULL) + if (camera_info_ptr_[stream_index] == NULL) { prepareStreamCalibData(stream_index); } @@ -165,14 +163,17 @@ namespace realsense_camera bool BaseNodelet::connectToCamera() { + std::string serial_no; + std::string usb_port_id; + rs_context_ = rs_create_context(RS_API_VERSION, &rs_error_); checkError(); - num_of_cameras_ = rs_get_device_count(rs_context_, &rs_error_); + int num_of_cameras = rs_get_device_count(rs_context_, &rs_error_); checkError(); // Exit with error if no cameras are connected. - if (num_of_cameras_ < 1) + if (num_of_cameras < 1) { ROS_ERROR_STREAM(nodelet_name_ << " - No cameras detected!"); rs_delete_context(rs_context_, &rs_error_); @@ -181,10 +182,13 @@ namespace realsense_camera } // Print list of all cameras found - listCameras(); + listCameras(num_of_cameras); + + pnh_.getParam("serial_no", serial_no); + pnh_.getParam("usb_port_id", usb_port_id); // Exit with error if no serial number or usb_port_id is specified and multiple cameras are detected. - if (serial_no_.empty() && usb_port_id_.empty() && num_of_cameras_ > 1) + if (serial_no.empty() && usb_port_id.empty() && num_of_cameras > 1) { ROS_ERROR_STREAM(nodelet_name_ << " - Multiple cameras detected but no input serial_no or usb_port_id specified"); rs_delete_context(rs_context_, &rs_error_); @@ -196,12 +200,13 @@ namespace realsense_camera rs_device_ = nullptr; // find camera - for (int i = 0; i < num_of_cameras_; i++) + for (int i = 0; i < num_of_cameras; i++) { rs_device* rs_detected_device = rs_get_device(rs_context_, i, &rs_error_); + // check serial_no and usb_port_id - if ((serial_no_.empty() || serial_no_ == rs_get_device_serial(rs_detected_device, &rs_error_)) && - (usb_port_id_.empty() || usb_port_id_ == rs_get_device_usb_port_id(rs_detected_device, &rs_error_))) + if ((serial_no.empty() || serial_no == rs_get_device_serial(rs_detected_device, &rs_error_)) && + (usb_port_id.empty() || usb_port_id == rs_get_device_usb_port_id(rs_detected_device, &rs_error_))) { // device found rs_device_= rs_detected_device; @@ -213,9 +218,11 @@ namespace realsense_camera { // camera not found string error_msg = " - Couldn't find camera to connect with "; - error_msg += "serial_no = " + serial_no_ + ", "; - error_msg += "usb_port_id = " + usb_port_id_; + error_msg += "serial_no = " + serial_no + ", "; + error_msg += "usb_port_id = " + usb_port_id; + ROS_ERROR_STREAM(nodelet_name_ << error_msg); + rs_delete_context(rs_context_, &rs_error_); checkError(); return false; @@ -230,12 +237,12 @@ namespace realsense_camera // Enable streams. if (enable_color_ == true) { - enableStream(RS_STREAM_COLOR, color_width_, color_height_, COLOR_FORMAT, color_fps_); + enableStream(RS_STREAM_COLOR, width_[RS_STREAM_COLOR], height_[RS_STREAM_COLOR], COLOR_FORMAT, fps_[RS_STREAM_COLOR]); } if (enable_depth_ == true) { - enableStream(RS_STREAM_DEPTH, depth_width_, depth_height_, DEPTH_FORMAT, depth_fps_); - enableStream(RS_STREAM_INFRARED, depth_width_, depth_height_, IR_FORMAT, depth_fps_); + enableStream(RS_STREAM_DEPTH, width_[RS_STREAM_DEPTH], height_[RS_STREAM_DEPTH], DEPTH_FORMAT, fps_[RS_STREAM_DEPTH]); + enableStream(RS_STREAM_INFRARED, width_[RS_STREAM_DEPTH], height_[RS_STREAM_DEPTH], IR_FORMAT, fps_[RS_STREAM_DEPTH]); } getCameraOptions(); setStaticCameraOptions(); @@ -252,14 +259,15 @@ namespace realsense_camera return true; } - void BaseNodelet::listCameras() + void BaseNodelet::listCameras(int num_of_cameras) { // print list of detected cameras std::string detected_camera_msg = " - Detected the following cameras:"; - for (int i = 0; i < num_of_cameras_; i++) + for (int i = 0; i < num_of_cameras; i++) { // get device rs_device* rs_detected_device = rs_get_device(rs_context_, i, &rs_error_); + // print device details detected_camera_msg = detected_camera_msg + "\n\t\t\t\t- Serial No: " + rs_get_device_serial(rs_detected_device, &rs_error_) + @@ -283,6 +291,7 @@ namespace realsense_camera if (rs_device_supports_option(rs_device_, o.opt, &rs_error_)) { rs_get_device_option_range(rs_device_, o.opt, &o.min, &o.max, &o.step, 0); + // Skip the camera options where min and max values are the same. if (o.min != o.max) { @@ -301,9 +310,9 @@ namespace realsense_camera // Prepare camera for enabled streams (color/depth/infrared) fillStreamEncoding(); - image_[(uint32_t) RS_STREAM_COLOR] = cv::Mat(color_height_, color_width_, CV_8UC3, cv::Scalar (0, 0, 0)); - image_[(uint32_t) RS_STREAM_DEPTH] = cv::Mat(depth_height_, depth_width_, CV_16UC1, cv::Scalar (0)); - image_[(uint32_t) RS_STREAM_INFRARED] = cv::Mat(depth_height_, depth_width_, CV_8UC1, cv::Scalar (0)); + image_[RS_STREAM_COLOR] = cv::Mat(height_[RS_STREAM_COLOR], width_[RS_STREAM_COLOR], CV_8UC3, cv::Scalar (0, 0, 0)); + image_[RS_STREAM_DEPTH] = cv::Mat(height_[RS_STREAM_DEPTH], width_[RS_STREAM_DEPTH], CV_16UC1, cv::Scalar (0)); + image_[RS_STREAM_INFRARED] = cv::Mat(height_[RS_STREAM_DEPTH], width_[RS_STREAM_DEPTH], CV_8UC1, cv::Scalar (0)); } /* @@ -315,33 +324,33 @@ namespace realsense_camera rs_get_stream_intrinsics(rs_device_, stream_index, &intrinsic, &rs_error_); checkError(); - camera_info_[stream_index] = new sensor_msgs::CameraInfo(); - camera_info_ptr_[stream_index] = sensor_msgs::CameraInfoPtr (camera_info_[stream_index]); + sensor_msgs::CameraInfo * camera_info = new sensor_msgs::CameraInfo(); + camera_info_ptr_[stream_index] = sensor_msgs::CameraInfoPtr (camera_info); - camera_info_[stream_index]->header.frame_id = frame_id_[stream_index]; - camera_info_[stream_index]->width = intrinsic.width; - camera_info_[stream_index]->height = intrinsic.height; + camera_info->header.frame_id = frame_id_[stream_index]; + camera_info->width = intrinsic.width; + camera_info->height = intrinsic.height; - camera_info_[stream_index]->K.at(0) = intrinsic.fx; - camera_info_[stream_index]->K.at(2) = intrinsic.ppx; - camera_info_[stream_index]->K.at(4) = intrinsic.fy; - camera_info_[stream_index]->K.at(5) = intrinsic.ppy; - camera_info_[stream_index]->K.at(8) = 1; + camera_info->K.at(0) = intrinsic.fx; + camera_info->K.at(2) = intrinsic.ppx; + camera_info->K.at(4) = intrinsic.fy; + camera_info->K.at(5) = intrinsic.ppy; + camera_info->K.at(8) = 1; - camera_info_[stream_index]->P.at(0) = camera_info_[stream_index]->K.at(0); - camera_info_[stream_index]->P.at(1) = 0; - camera_info_[stream_index]->P.at(2) = camera_info_[stream_index]->K.at(2); - camera_info_[stream_index]->P.at(3) = 0; + camera_info->P.at(0) = camera_info->K.at(0); + camera_info->P.at(1) = 0; + camera_info->P.at(2) = camera_info->K.at(2); + camera_info->P.at(3) = 0; - camera_info_[stream_index]->P.at(4) = 0; - camera_info_[stream_index]->P.at(5) = camera_info_[stream_index]->K.at(4); - camera_info_[stream_index]->P.at(6) = camera_info_[stream_index]->K.at(5); - camera_info_[stream_index]->P.at(7) = 0; + camera_info->P.at(4) = 0; + camera_info->P.at(5) = camera_info->K.at(4); + camera_info->P.at(6) = camera_info->K.at(5); + camera_info->P.at(7) = 0; - camera_info_[stream_index]->P.at(8) = 0; - camera_info_[stream_index]->P.at(9) = 0; - camera_info_[stream_index]->P.at(10) = 1; - camera_info_[stream_index]->P.at(11) = 0; + camera_info->P.at(8) = 0; + camera_info->P.at(9) = 0; + camera_info->P.at(10) = 1; + camera_info->P.at(11) = 0; if (stream_index == RS_STREAM_DEPTH) { @@ -349,27 +358,27 @@ namespace realsense_camera rs_extrinsics z_extrinsic; rs_get_device_extrinsics(rs_device_, RS_STREAM_DEPTH, RS_STREAM_COLOR, &z_extrinsic, &rs_error_); checkError(); - camera_info_[stream_index]->P.at(3) = z_extrinsic.translation[0]; // Tx - camera_info_[stream_index]->P.at(7) = z_extrinsic.translation[1]; // Ty - camera_info_[stream_index]->P.at(11) = z_extrinsic.translation[2]; // Tz + camera_info->P.at(3) = z_extrinsic.translation[0]; // Tx + camera_info->P.at(7) = z_extrinsic.translation[1]; // Ty + camera_info->P.at(11) = z_extrinsic.translation[2]; // Tz } - camera_info_[stream_index]->distortion_model = "plumb_bob"; + camera_info->distortion_model = "plumb_bob"; // set R (rotation matrix) values to identity matrix - camera_info_[stream_index]->R.at(0) = (double) 1; - camera_info_[stream_index]->R.at(1) = (double) 0; - camera_info_[stream_index]->R.at(2) = (double) 0; - camera_info_[stream_index]->R.at(3) = (double) 0; - camera_info_[stream_index]->R.at(4) = (double) 1; - camera_info_[stream_index]->R.at(5) = (double) 0; - camera_info_[stream_index]->R.at(6) = (double) 0; - camera_info_[stream_index]->R.at(7) = (double) 0; - camera_info_[stream_index]->R.at(8) = (double) 1; + camera_info->R.at(0) = (double) 1; + camera_info->R.at(1) = (double) 0; + camera_info->R.at(2) = (double) 0; + camera_info->R.at(3) = (double) 0; + camera_info->R.at(4) = (double) 1; + camera_info->R.at(5) = (double) 0; + camera_info->R.at(6) = (double) 0; + camera_info->R.at(7) = (double) 0; + camera_info->R.at(8) = (double) 1; for (int i = 0; i < 5; i++) { - camera_info_[stream_index]->D.push_back(intrinsic.coeffs[i]); + camera_info->D.push_back(intrinsic.coeffs[i]); } } @@ -400,26 +409,19 @@ namespace realsense_camera */ void BaseNodelet::setStreamOptions() { - pnh_.getParam("serial_no", serial_no_); - pnh_.getParam("usb_port_id", usb_port_id_); - pnh_.getParam("camera", camera_); - pnh_.param("mode", mode_, DEFAULT_MODE); pnh_.param("enable_depth", enable_depth_, ENABLE_DEPTH); pnh_.param("enable_color", enable_color_, ENABLE_COLOR); pnh_.param("enable_pointcloud", enable_pointcloud_, ENABLE_PC); pnh_.param("enable_tf", enable_tf_, ENABLE_TF); - pnh_.param("depth_width", depth_width_, DEPTH_WIDTH); - pnh_.param("depth_height", depth_height_, DEPTH_HEIGHT); - pnh_.param("color_width", color_width_, COLOR_WIDTH); - pnh_.param("color_height", color_height_, COLOR_HEIGHT); - pnh_.param("depth_fps", depth_fps_, DEPTH_FPS); - pnh_.param("color_fps", color_fps_, COLOR_FPS); - pnh_.param("base_frame_id", base_frame_id_, DEFAULT_BASE_FRAME_ID); - pnh_.param("depth_frame_id", depth_frame_id_, DEFAULT_DEPTH_FRAME_ID); - pnh_.param("color_frame_id", color_frame_id_, DEFAULT_COLOR_FRAME_ID); - pnh_.param("depth_optical_frame_id", depth_optical_frame_id_, DEFAULT_DEPTH_OPTICAL_FRAME_ID); - pnh_.param("color_optical_frame_id", color_optical_frame_id_, DEFAULT_COLOR_OPTICAL_FRAME_ID); - pnh_.param("ir_frame_id", ir_frame_id_, DEFAULT_IR_FRAME_ID); + pnh_.param("depth_width", width_[RS_STREAM_DEPTH], DEPTH_WIDTH); + pnh_.param("depth_height", height_[RS_STREAM_DEPTH], DEPTH_HEIGHT); + pnh_.param("color_width", width_[RS_STREAM_COLOR], COLOR_WIDTH); + pnh_.param("color_height", height_[RS_STREAM_COLOR], COLOR_HEIGHT); + pnh_.param("depth_fps", fps_[RS_STREAM_DEPTH], DEPTH_FPS); + pnh_.param("color_fps", fps_[RS_STREAM_COLOR], COLOR_FPS); + pnh_.param("depth_optical_frame_id", frame_id_[RS_STREAM_DEPTH], DEFAULT_DEPTH_OPTICAL_FRAME_ID); + pnh_.param("color_optical_frame_id", frame_id_[RS_STREAM_COLOR], DEFAULT_COLOR_OPTICAL_FRAME_ID); + pnh_.param("ir_frame_id", frame_id_[RS_STREAM_INFRARED], DEFAULT_IR_FRAME_ID); } @@ -442,12 +444,12 @@ namespace realsense_camera */ void BaseNodelet::fillStreamEncoding() { - stream_encoding_[(uint32_t) RS_STREAM_COLOR] = "rgb8"; - stream_step_[(uint32_t) RS_STREAM_COLOR] = color_width_ * sizeof (unsigned char) * 3; - stream_encoding_[(uint32_t) RS_STREAM_DEPTH] = sensor_msgs::image_encodings::TYPE_16UC1; - stream_step_[(uint32_t) RS_STREAM_DEPTH] = depth_width_ * sizeof (uint16_t); - stream_encoding_[(uint32_t) RS_STREAM_INFRARED] = sensor_msgs::image_encodings::TYPE_8UC1; - stream_step_[(uint32_t) RS_STREAM_INFRARED] = depth_width_ * sizeof (unsigned char); + stream_encoding_[RS_STREAM_COLOR] = "rgb8"; + stream_step_[RS_STREAM_COLOR] = width_[RS_STREAM_COLOR] * sizeof (unsigned char) * 3; + stream_encoding_[RS_STREAM_DEPTH] = sensor_msgs::image_encodings::TYPE_16UC1; + stream_step_[RS_STREAM_DEPTH] = width_[RS_STREAM_DEPTH] * sizeof (uint16_t); + stream_encoding_[RS_STREAM_INFRARED] = sensor_msgs::image_encodings::TYPE_8UC1; + stream_step_[RS_STREAM_INFRARED] = width_[RS_STREAM_DEPTH] * sizeof (unsigned char); } /* @@ -487,8 +489,8 @@ namespace realsense_camera checkError(); } - enableStream(RS_STREAM_DEPTH, depth_width_, depth_height_, DEPTH_FORMAT, depth_fps_); - enableStream(RS_STREAM_INFRARED, depth_width_, depth_height_, IR_FORMAT, depth_fps_); + enableStream(RS_STREAM_DEPTH, width_[RS_STREAM_DEPTH], height_[RS_STREAM_DEPTH], DEPTH_FORMAT, fps_[RS_STREAM_DEPTH]); + enableStream(RS_STREAM_INFRARED, width_[RS_STREAM_DEPTH], height_[RS_STREAM_DEPTH], IR_FORMAT, fps_[RS_STREAM_DEPTH]); if (rs_is_device_streaming(rs_device_, 0) == 0) { @@ -502,7 +504,8 @@ namespace realsense_camera { rs_wait_for_frames(rs_device_, &rs_error_); checkError(); - time_stamp_ = ros::Time::now(); + + ros::Time time_stamp = ros::Time::now(); bool duplicate_depth_color = false; for (int stream_index = 0; stream_index < num_streams_; ++stream_index) @@ -521,7 +524,7 @@ namespace realsense_camera image_[stream_index]).toImageMsg(); msg->header.frame_id = frame_id_[stream_index]; - msg->header.stamp = time_stamp_; // Publish timestamp to synchronize frames. + msg->header.stamp = time_stamp; // Publish timestamp to synchronize frames. msg->width = image_[stream_index].cols; msg->height = image_[stream_index].rows; msg->is_bigendian = false; @@ -545,15 +548,15 @@ namespace realsense_camera rs_is_stream_enabled(rs_device_, RS_STREAM_DEPTH, 0) == 1 && enable_pointcloud_ == true && (duplicate_depth_color == false)) // Skip publishing PointCloud if Depth and/or Color frame was duplicate { - if (camera_publisher_[(uint32_t) RS_STREAM_DEPTH].getNumSubscribers() <= 0) + if (camera_publisher_[RS_STREAM_DEPTH].getNumSubscribers() <= 0) { prepareStreamData(RS_STREAM_DEPTH); } - if (camera_publisher_[(uint32_t) RS_STREAM_COLOR].getNumSubscribers() <= 0) + if (camera_publisher_[RS_STREAM_COLOR].getNumSubscribers() <= 0) { prepareStreamData(RS_STREAM_COLOR); } - publishPointCloud(image_[(uint32_t) RS_STREAM_COLOR]); + publishPointCloud(image_[RS_STREAM_COLOR], time_stamp); } } } @@ -562,7 +565,7 @@ namespace realsense_camera /* * Publish pointcloud. */ - void BaseNodelet::publishPointCloud (cv::Mat & image_color) + void BaseNodelet::publishPointCloud (cv::Mat & image_color, ros::Time time_stamp) { // Publish pointcloud only if there is at least one subscriber. if (pointcloud_publisher_.getNumSubscribers() > 0) @@ -584,9 +587,9 @@ namespace realsense_camera // Convert pointcloud from the camera to pointcloud object for ROS. sensor_msgs::PointCloud2 msg_pointcloud; - msg_pointcloud.width = depth_width_; - msg_pointcloud.height = depth_height_; - msg_pointcloud.header.stamp = time_stamp_; + msg_pointcloud.width = width_[RS_STREAM_DEPTH]; + msg_pointcloud.height = height_[RS_STREAM_DEPTH]; + msg_pointcloud.header.stamp = time_stamp; msg_pointcloud.is_dense = true; sensor_msgs::PointCloud2Modifier modifier(msg_pointcloud); @@ -688,6 +691,13 @@ namespace realsense_camera rs_get_device_extrinsics(rs_device_, RS_STREAM_DEPTH, RS_STREAM_COLOR, &z_extrinsic, &rs_error_); checkError(); + std::string base_frame_id; + std::string color_frame_id; + std::string depth_frame_id; + pnh_.param("base_frame_id", base_frame_id, DEFAULT_BASE_FRAME_ID); + pnh_.param("color_frame_id", color_frame_id, DEFAULT_COLOR_FRAME_ID); + pnh_.param("depth_frame_id", depth_frame_id, DEFAULT_DEPTH_FRAME_ID); + ros::Duration sleeper(0.1); // 100ms while (ros::ok()) @@ -698,24 +708,24 @@ namespace realsense_camera // transform base frame to depth frame tr.setOrigin(tf::Vector3(z_extrinsic.translation[2], -z_extrinsic.translation[0], -z_extrinsic.translation[1])); tr.setRotation(tf::Quaternion(0, 0, 0, 1)); - tf_broadcaster.sendTransform(tf::StampedTransform(tr, time_stamp, base_frame_id_, depth_frame_id_)); + tf_broadcaster.sendTransform(tf::StampedTransform(tr, time_stamp, base_frame_id, depth_frame_id)); // transform depth frame to depth optical frame tr.setOrigin(tf::Vector3(0,0,0)); q.setEuler( M_PI/2, 0.0, -M_PI/2 ); tr.setRotation( q ); - tf_broadcaster.sendTransform(tf::StampedTransform(tr, time_stamp, depth_frame_id_, depth_optical_frame_id_)); + tf_broadcaster.sendTransform(tf::StampedTransform(tr, time_stamp, depth_frame_id, frame_id_[RS_STREAM_DEPTH])); // transform base frame to color frame (these are the same) tr.setOrigin(tf::Vector3(0,0,0)); tr.setRotation(tf::Quaternion(0, 0, 0, 1)); - tf_broadcaster.sendTransform(tf::StampedTransform(tr, time_stamp, base_frame_id_, color_frame_id_)); + tf_broadcaster.sendTransform(tf::StampedTransform(tr, time_stamp, base_frame_id, color_frame_id)); // transform color frame to color optical frame tr.setOrigin(tf::Vector3(0,0,0)); q.setEuler( M_PI/2, 0.0, -M_PI/2 ); tr.setRotation( q ); - tf_broadcaster.sendTransform(tf::StampedTransform(tr, time_stamp, color_frame_id_, color_optical_frame_id_)); + tf_broadcaster.sendTransform(tf::StampedTransform(tr, time_stamp, color_frame_id, frame_id_[RS_STREAM_COLOR])); sleeper.sleep(); // need sleep or transform won't publish correctly } diff --git a/realsense_camera/src/r200_nodelet.cpp b/realsense_camera/src/r200_nodelet.cpp index 92e94bfec2..40f84f0287 100644 --- a/realsense_camera/src/r200_nodelet.cpp +++ b/realsense_camera/src/r200_nodelet.cpp @@ -45,10 +45,10 @@ namespace realsense_camera { // set member vars used in base class nodelet_name_ = getName(); - num_streams_ = R200_STREAM_COUNT; - max_z_ = R200_MAX_Z; nh_ = getNodeHandle(); pnh_ = getPrivateNodeHandle(); + num_streams_ = R200_STREAM_COUNT; + max_z_ = R200_MAX_Z; // create dynamic reconfigure server - this must be done before calling base class onInit() // onInit() calls setStaticCameraOptions() which relies on this being set already @@ -58,7 +58,6 @@ namespace realsense_camera BaseNodelet::onInit(); // Set up the IR2 frame and topics - frame_id_[RS_STREAM_INFRARED2] = ir2_frame_id_; image_transport::ImageTransport it (nh_); camera_publisher_[RS_STREAM_INFRARED2] = it.advertiseCamera(IR2_TOPIC, 1); @@ -74,7 +73,7 @@ namespace realsense_camera BaseNodelet::enableStream(stream_index, width, height, format, fps); if (stream_index == RS_STREAM_INFRARED) { - enableStream(RS_STREAM_INFRARED2, depth_width_, depth_height_, IR_FORMAT, depth_fps_); + enableStream(RS_STREAM_INFRARED2, width_[RS_STREAM_DEPTH], height_[RS_STREAM_DEPTH], IR_FORMAT, fps_[RS_STREAM_DEPTH]); } } @@ -135,22 +134,24 @@ namespace realsense_camera if (config.r200_lr_auto_exposure_enabled == 1) { - if (config.r200_auto_exposure_top_edge >= depth_height_) + if (config.r200_auto_exposure_top_edge >= height_[RS_STREAM_DEPTH]) { - config.r200_auto_exposure_top_edge = depth_height_ - 1; + config.r200_auto_exposure_top_edge = height_[RS_STREAM_DEPTH] - 1; } - if (config.r200_auto_exposure_bottom_edge >= depth_height_) + if (config.r200_auto_exposure_bottom_edge >= height_[RS_STREAM_DEPTH]) { - config.r200_auto_exposure_bottom_edge = depth_height_ - 1; + config.r200_auto_exposure_bottom_edge = height_[RS_STREAM_DEPTH] - 1; } - if (config.r200_auto_exposure_left_edge >= depth_width_) + if (config.r200_auto_exposure_left_edge >= width_[RS_STREAM_DEPTH]) { - config.r200_auto_exposure_left_edge = depth_width_ - 1; + config.r200_auto_exposure_left_edge = width_[RS_STREAM_DEPTH] - 1; } - if (config.r200_auto_exposure_right_edge >= depth_width_) + if (config.r200_auto_exposure_right_edge >= width_[RS_STREAM_DEPTH]) { - config.r200_auto_exposure_right_edge = depth_width_ - 1; + config.r200_auto_exposure_right_edge = width_[RS_STREAM_DEPTH] - 1; } + + double edge_values_[4]; edge_values_[0] = config.r200_auto_exposure_left_edge; edge_values_[1] = config.r200_auto_exposure_top_edge; edge_values_[2] = config.r200_auto_exposure_right_edge; @@ -168,7 +169,7 @@ namespace realsense_camera // call base class method first BaseNodelet::allocateResources(); // set IR2 image buffer - image_[(uint32_t) RS_STREAM_INFRARED2] = cv::Mat(depth_height_, depth_width_, CV_8UC1, cv::Scalar (0)); + image_[(uint32_t) RS_STREAM_INFRARED2] = cv::Mat(height_[RS_STREAM_DEPTH], width_[RS_STREAM_DEPTH], CV_8UC1, cv::Scalar (0)); } /* @@ -179,7 +180,7 @@ namespace realsense_camera // call base class method first BaseNodelet::setStreamOptions(); // setup R200 specific frame - pnh_.param("ir2_frame_id", ir2_frame_id_, DEFAULT_IR2_FRAME_ID); + pnh_.param("ir2_frame_id", frame_id_[RS_STREAM_INFRARED2], DEFAULT_IR2_FRAME_ID); } /* @@ -191,7 +192,7 @@ namespace realsense_camera BaseNodelet::fillStreamEncoding(); // Setup IR2 stream stream_encoding_[(uint32_t) RS_STREAM_INFRARED2] = sensor_msgs::image_encodings::TYPE_8UC1; - stream_step_[(uint32_t) RS_STREAM_INFRARED2] = depth_width_ * sizeof (unsigned char); + stream_step_[(uint32_t) RS_STREAM_INFRARED2] = width_[RS_STREAM_DEPTH] * sizeof (unsigned char); } /* From c451c81f7e35851b427a672562f4150cd9a2e346 Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Fri, 24 Jun 2016 21:01:20 -0700 Subject: [PATCH 120/124] Refactored launch and test files realsense_r200_nodelet.launch.xml ==> nodelet_rgbd.launch.xml realsense_r200_multiple_cameras.launch.xml ==> nodelet.launch.xml realsense_r200_nodelet_standalone_preset.launch ==> r200_nodelet_default.launch realsense_r200_nodelet_standalone_manual.launch ==> r200_nodelet_modify_params.launch realsense_r200_rgbd.launch ==> r200_nodelet_rgbd.launch realsense_r200_multiple_cameras.launch ==> r200_nodelet_multiple_cameras.launch Removed realsense_r200_navigation.launch realsense_r200_color_only.test ==> r200_nodelet_disable_depth.test realsense_r200_depth_only.test ==> r200_nodelet_disable_color.test realsense_r200_rgbd.test ==> r200_nodelet_rgbd.test realsense_r200_resolution.test ==> r200_nodelet_resolution.test realsense_r200_stream_options_params.launch ==> r200_nodelet_modify_params.test realsense_r200_static_camera_options_params.launch ==> r200_nodelet_static_params.launch realsense_r200_dynamic_camera_options_params.launch ==> r200_nodelet_dynamic_params.launch --- realsense_camera/README.md | 30 +++++------- .../launch/includes/nodelet.launch.xml | 35 ++++++++++++++ ...let.launch.xml => nodelet_rgbd.launch.xml} | 31 +++++++------ ...realsense_r200_multiple_cameras.launch.xml | 31 ------------- .../launch/r200_nodelet_default.launch | 18 ++++++++ .../launch/r200_nodelet_modify_params.launch | 46 +++++++++++++++++++ .../r200_nodelet_multiple_cameras.launch | 24 ++++++++++ ...0_rgbd.launch => r200_nodelet_rgbd.launch} | 32 +++++++------ .../realsense_r200_multiple_cameras.launch | 28 ----------- .../launch/realsense_r200_navigation.launch | 23 ---------- ...ense_r200_nodelet_standalone_manual.launch | 36 --------------- ...ense_r200_nodelet_standalone_preset.launch | 23 ---------- .../test/r200_nodelet_disable_color.test | 16 +++++++ .../test/r200_nodelet_disable_depth.test | 16 +++++++ ...nch => r200_nodelet_dynamic_params.launch} | 2 +- .../test/r200_nodelet_modify_params.test | 28 +++++++++++ .../test/r200_nodelet_resolution.test | 26 +++++++++++ realsense_camera/test/r200_nodelet_rgbd.test | 8 ++++ ...unch => r200_nodelet_static_params.launch} | 2 +- .../test/realsense_r200_color_only.test | 9 ---- .../test/realsense_r200_depth_only.test | 9 ---- .../test/realsense_r200_resolution.test | 14 ------ .../test/realsense_r200_rgbd.test | 7 --- ...ealsense_r200_stream_options_params.launch | 43 ----------------- 24 files changed, 266 insertions(+), 271 deletions(-) create mode 100644 realsense_camera/launch/includes/nodelet.launch.xml rename realsense_camera/launch/includes/{realsense_r200_nodelet.launch.xml => nodelet_rgbd.launch.xml} (81%) delete mode 100644 realsense_camera/launch/includes/realsense_r200_multiple_cameras.launch.xml create mode 100644 realsense_camera/launch/r200_nodelet_default.launch create mode 100644 realsense_camera/launch/r200_nodelet_modify_params.launch create mode 100644 realsense_camera/launch/r200_nodelet_multiple_cameras.launch rename realsense_camera/launch/{realsense_r200_rgbd.launch => r200_nodelet_rgbd.launch} (85%) delete mode 100644 realsense_camera/launch/realsense_r200_multiple_cameras.launch delete mode 100644 realsense_camera/launch/realsense_r200_navigation.launch delete mode 100644 realsense_camera/launch/realsense_r200_nodelet_standalone_manual.launch delete mode 100644 realsense_camera/launch/realsense_r200_nodelet_standalone_preset.launch create mode 100644 realsense_camera/test/r200_nodelet_disable_color.test create mode 100644 realsense_camera/test/r200_nodelet_disable_depth.test rename realsense_camera/test/{realsense_r200_dynamic_camera_options_params.launch => r200_nodelet_dynamic_params.launch} (98%) create mode 100644 realsense_camera/test/r200_nodelet_modify_params.test create mode 100644 realsense_camera/test/r200_nodelet_resolution.test create mode 100644 realsense_camera/test/r200_nodelet_rgbd.test rename realsense_camera/test/{realsense_r200_static_camera_options_params.launch => r200_nodelet_static_params.launch} (97%) delete mode 100644 realsense_camera/test/realsense_r200_color_only.test delete mode 100644 realsense_camera/test/realsense_r200_depth_only.test delete mode 100644 realsense_camera/test/realsense_r200_resolution.test delete mode 100644 realsense_camera/test/realsense_r200_rgbd.test delete mode 100644 realsense_camera/test/realsense_r200_stream_options_params.launch diff --git a/realsense_camera/README.md b/realsense_camera/README.md index bf3d96c0a8..e4e6337f74 100644 --- a/realsense_camera/README.md +++ b/realsense_camera/README.md @@ -26,10 +26,10 @@ If this does not work, you should first fix this issue before continuing with th Successful execution of command will build target “realsense_camera_nodelet” Sample launch files are available in "realsense_camera/launch" directory -* realsense_r200_rgbd.launch -* realsense_r200_nodelet_standalone_preset.launch -* realsense_r200_nodelet_standalone_manual.launch -* realsense_r200_multiple_cameras.launch +* r200_nodelet_rgbd.launch +* r200_nodelet_default.launch +* r200_nodelet_modify_params.launch +* r200_nodelet_multiple_cameras.launch ###Package Features: @@ -79,8 +79,7 @@ IR2 camera Stream parameters: serial_no (string, default: blank) Specify the serial_no to uniquely connect to a camera, especially if multiple cameras are detected by the nodelet. - You may get the serial_no from the info stream by launching "realsense_r200_nodelet_standalone_preset.launch" - one at a time for each camera. + You may get the serial_no from the info stream by launching "r200_nodelet_default.launch" usb_port_id (string, default: blank) Alternatively to serial_no, this can be used to connect to a camera by its USB Port ID, which is a Bus Number-Port Number in the format "Bus#-Port#". If used with serial_no, both must match correctly for @@ -185,7 +184,7 @@ Command to change dynamic parameters using commandline: ####Getting Started Use the following command to launch the camera nodelet. You will notice the camera light up. - $ roslaunch realsense_camera realsense_r200_nodelet_standalone_preset.launch + $ roslaunch realsense_camera r200_nodelet_default.launch If you would like to create or use your own launch files, the nodelet name for the R200 camera is R200Nodelet. See the sample launch files for examples of how to launch the nodelet. @@ -227,11 +226,10 @@ For viewing supported camera settings with current values: ####Launching Multiple Cameras For running multiple cameras simultaneously: Option 1: Using single nodelet manager for all the cameras -* Use "realsense_r200_multiple_cameras.launch". - * For the "num_worker_threads" argument, allocate at least 1 thread for each camera. +* Use "r200_nodelet_multiple_cameras.launch". Option 2: Using separate nodelet manager for each camera -* Create ".launch" files similar to "realsense_r200_rgbd.launch" for each camera. +* Create ".launch" files similar to "r200_nodelet_rgbd.launch" for each camera. * You may choose to include (or not) the "processing.launch.xml" based on your requirement. * Launch the ".launch" files for each camera in separate terminals. @@ -248,11 +246,11 @@ The Unit Tests can be executed using either of the methods: Using `rostest` command with test files $ rostest realsense_camera - E.g. rostest realsense_camera realsense_r200_depth_only.test + E.g. rostest realsense_camera r200_nodelet_disable_color.test Using `rosrun` command - $ roslaunch realsense_camera realsense_r200_nodelet_standalone_manual.launch + $ roslaunch realsense_camera r200_nodelet_modify_params.launch $ rosrun realsense_camera realsense_camera_test E.g. rosrun realsense_camera realsense_camera_test enable_depth 1 depth_encoding 16UC1 depth_height 360 depth_width 480 depth_step 960 enable_color 1 color_encoding rgb8 color_height 480 color_width 640 color_step 1920 @@ -260,10 +258,6 @@ Using `rosrun` command Both these methods first starts the nodelet and then executes all the unit tests. Sample test files are available in "realsense_camera/test" directory -* realsense_r200_rgbd.test -* realsense_r200_color_only.test -* realsense_r200_depth_only.test -* realsense_r200_resolution.test ###Developer API: Refer to the following: @@ -280,11 +274,11 @@ Refer to the following: * Generating a Depth Registered Point Cloud is very memory intensive. The topic /camera/depth_registered/points, generated by launch file -"realsense_r200_rgbd.launch", works best at 30 fps using 640x480 resolution +"r200_nodelet_rgbd.launch", works best at 30 fps using 640x480 resolution on a system with 16GB of RAM. * The camera does not provide hardware based depth registration/projector data. -Hence the launch file "realsense_r200_rgbd.launch" will not generate data for the following topics: +Hence the launch file "r200_nodelet_rgbd.launch" will not generate data for the following topics: * /camera/depth_registered/hw_registered/image_rect_raw * /camera/depth_registered/hw_registered/image_rect * /camera/depth_registered/image diff --git a/realsense_camera/launch/includes/nodelet.launch.xml b/realsense_camera/launch/includes/nodelet.launch.xml new file mode 100644 index 0000000000..6a25be991b --- /dev/null +++ b/realsense_camera/launch/includes/nodelet.launch.xml @@ -0,0 +1,35 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/realsense_camera/launch/includes/realsense_r200_nodelet.launch.xml b/realsense_camera/launch/includes/nodelet_rgbd.launch.xml similarity index 81% rename from realsense_camera/launch/includes/realsense_r200_nodelet.launch.xml rename to realsense_camera/launch/includes/nodelet_rgbd.launch.xml index 804a666b77..1735a58844 100644 --- a/realsense_camera/launch/includes/realsense_r200_nodelet.launch.xml +++ b/realsense_camera/launch/includes/nodelet_rgbd.launch.xml @@ -1,7 +1,7 @@ + - - + @@ -12,37 +12,38 @@ - + + - - + + - - - + + + - - + - + - - + + diff --git a/realsense_camera/launch/includes/realsense_r200_multiple_cameras.launch.xml b/realsense_camera/launch/includes/realsense_r200_multiple_cameras.launch.xml deleted file mode 100644 index 33f3f702aa..0000000000 --- a/realsense_camera/launch/includes/realsense_r200_multiple_cameras.launch.xml +++ /dev/null @@ -1,31 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/realsense_camera/launch/r200_nodelet_default.launch b/realsense_camera/launch/r200_nodelet_default.launch new file mode 100644 index 0000000000..2d189cacd6 --- /dev/null +++ b/realsense_camera/launch/r200_nodelet_default.launch @@ -0,0 +1,18 @@ + + + + + + + + + + + + + + + + + + diff --git a/realsense_camera/launch/r200_nodelet_modify_params.launch b/realsense_camera/launch/r200_nodelet_modify_params.launch new file mode 100644 index 0000000000..7b706a2cef --- /dev/null +++ b/realsense_camera/launch/r200_nodelet_modify_params.launch @@ -0,0 +1,46 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/realsense_camera/launch/r200_nodelet_multiple_cameras.launch b/realsense_camera/launch/r200_nodelet_multiple_cameras.launch new file mode 100644 index 0000000000..d5ea1879a3 --- /dev/null +++ b/realsense_camera/launch/r200_nodelet_multiple_cameras.launch @@ -0,0 +1,24 @@ + + + + + + + + + + + + + + + + + + + + + + diff --git a/realsense_camera/launch/realsense_r200_rgbd.launch b/realsense_camera/launch/r200_nodelet_rgbd.launch similarity index 85% rename from realsense_camera/launch/realsense_r200_rgbd.launch rename to realsense_camera/launch/r200_nodelet_rgbd.launch index 9d3446429b..76d16fe737 100644 --- a/realsense_camera/launch/realsense_r200_rgbd.launch +++ b/realsense_camera/launch/r200_nodelet_rgbd.launch @@ -1,15 +1,18 @@ - + - + + + + - + @@ -18,9 +21,6 @@ - - - @@ -28,6 +28,13 @@ + + + + @@ -52,7 +59,6 @@ - @@ -63,26 +69,26 @@ + file="$(find realsense_camera)/launch/includes/nodelet_rgbd.launch.xml"> + + - - + - - + + - diff --git a/realsense_camera/launch/realsense_r200_multiple_cameras.launch b/realsense_camera/launch/realsense_r200_multiple_cameras.launch deleted file mode 100644 index d2ff3e6b98..0000000000 --- a/realsense_camera/launch/realsense_r200_multiple_cameras.launch +++ /dev/null @@ -1,28 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/realsense_camera/launch/realsense_r200_navigation.launch b/realsense_camera/launch/realsense_r200_navigation.launch deleted file mode 100644 index c98e022896..0000000000 --- a/realsense_camera/launch/realsense_r200_navigation.launch +++ /dev/null @@ -1,23 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - diff --git a/realsense_camera/launch/realsense_r200_nodelet_standalone_manual.launch b/realsense_camera/launch/realsense_r200_nodelet_standalone_manual.launch deleted file mode 100644 index da4eacde9d..0000000000 --- a/realsense_camera/launch/realsense_r200_nodelet_standalone_manual.launch +++ /dev/null @@ -1,36 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/realsense_camera/launch/realsense_r200_nodelet_standalone_preset.launch b/realsense_camera/launch/realsense_r200_nodelet_standalone_preset.launch deleted file mode 100644 index 57dce5b176..0000000000 --- a/realsense_camera/launch/realsense_r200_nodelet_standalone_preset.launch +++ /dev/null @@ -1,23 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - diff --git a/realsense_camera/test/r200_nodelet_disable_color.test b/realsense_camera/test/r200_nodelet_disable_color.test new file mode 100644 index 0000000000..bee6c68eca --- /dev/null +++ b/realsense_camera/test/r200_nodelet_disable_color.test @@ -0,0 +1,16 @@ + + + + + + + + + + + + + + + diff --git a/realsense_camera/test/r200_nodelet_disable_depth.test b/realsense_camera/test/r200_nodelet_disable_depth.test new file mode 100644 index 0000000000..5e878b899b --- /dev/null +++ b/realsense_camera/test/r200_nodelet_disable_depth.test @@ -0,0 +1,16 @@ + + + + + + + + + + + + + + + diff --git a/realsense_camera/test/realsense_r200_dynamic_camera_options_params.launch b/realsense_camera/test/r200_nodelet_dynamic_params.launch similarity index 98% rename from realsense_camera/test/realsense_r200_dynamic_camera_options_params.launch rename to realsense_camera/test/r200_nodelet_dynamic_params.launch index f1846e1de8..dc9149eeaa 100644 --- a/realsense_camera/test/realsense_r200_dynamic_camera_options_params.launch +++ b/realsense_camera/test/r200_nodelet_dynamic_params.launch @@ -2,7 +2,7 @@ Launch file for testing if the dynamic camera options get set correctly using params. Steps: - roslaunch realsense_camera realsense_r200_dynamic_camera_options_params.launch + roslaunch realsense_camera r200_nodelet_dynamic_params.launch rosrun realsense_camera tests_camera_core color_backlight_compensation 3 color_brightness 10 color_contrast 16 color_gain 18 color_gamma 100 color_hue 20 color_saturation 21 color_sharpness 7 color_enable_auto_white_balance 0 color_white_balance 3000 r200_lr_gain 200 r200_emitter_enabled 1 r200_lr_exposure 27 Verify that the "testCameraOptions" test pass. --> diff --git a/realsense_camera/test/r200_nodelet_modify_params.test b/realsense_camera/test/r200_nodelet_modify_params.test new file mode 100644 index 0000000000..d404a53a2c --- /dev/null +++ b/realsense_camera/test/r200_nodelet_modify_params.test @@ -0,0 +1,28 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/realsense_camera/test/r200_nodelet_resolution.test b/realsense_camera/test/r200_nodelet_resolution.test new file mode 100644 index 0000000000..2d3b5daae2 --- /dev/null +++ b/realsense_camera/test/r200_nodelet_resolution.test @@ -0,0 +1,26 @@ + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/realsense_camera/test/r200_nodelet_rgbd.test b/realsense_camera/test/r200_nodelet_rgbd.test new file mode 100644 index 0000000000..a51a254b55 --- /dev/null +++ b/realsense_camera/test/r200_nodelet_rgbd.test @@ -0,0 +1,8 @@ + + + + + + + + diff --git a/realsense_camera/test/realsense_r200_static_camera_options_params.launch b/realsense_camera/test/r200_nodelet_static_params.launch similarity index 97% rename from realsense_camera/test/realsense_r200_static_camera_options_params.launch rename to realsense_camera/test/r200_nodelet_static_params.launch index c362384a7f..170d9190b4 100644 --- a/realsense_camera/test/realsense_r200_static_camera_options_params.launch +++ b/realsense_camera/test/r200_nodelet_static_params.launch @@ -2,7 +2,7 @@ Launch file for testing if the static camera options get set correctly using params. Steps: - roslaunch realsense_camera realsense_r200_static_camera_options_params.launch + roslaunch realsense_camera r200_nodelet_static_params.launch rosrun realsense_camera tests_camera_core r200_depth_units 2 r200_depth_clamp_min 3 r200_depth_clamp_max 4 r200_depth_control_estimate_median_decrement 5 r200_depth_control_estimate_median_increment 6 r200_depth_control_median_threshold 7 r200_depth_control_score_minimum_threshold 8 r200_depth_control_score_maximum_threshold 9 r200_depth_control_texture_count_threshold 10 r200_depth_control_texture_difference_threshold 11 r200_depth_control_second_peak_threshold 12 r200_depth_control_neighbor_threshold 13 r200_depth_control_lr_threshold 14 Verify that the "testCameraOptions" test pass. --> diff --git a/realsense_camera/test/realsense_r200_color_only.test b/realsense_camera/test/realsense_r200_color_only.test deleted file mode 100644 index 5e1867033f..0000000000 --- a/realsense_camera/test/realsense_r200_color_only.test +++ /dev/null @@ -1,9 +0,0 @@ - - - - - - - - diff --git a/realsense_camera/test/realsense_r200_depth_only.test b/realsense_camera/test/realsense_r200_depth_only.test deleted file mode 100644 index be924c0b17..0000000000 --- a/realsense_camera/test/realsense_r200_depth_only.test +++ /dev/null @@ -1,9 +0,0 @@ - - - - - - - - diff --git a/realsense_camera/test/realsense_r200_resolution.test b/realsense_camera/test/realsense_r200_resolution.test deleted file mode 100644 index ef34a1f5cb..0000000000 --- a/realsense_camera/test/realsense_r200_resolution.test +++ /dev/null @@ -1,14 +0,0 @@ - - - - - - - - - - - - - diff --git a/realsense_camera/test/realsense_r200_rgbd.test b/realsense_camera/test/realsense_r200_rgbd.test deleted file mode 100644 index 8ed6427103..0000000000 --- a/realsense_camera/test/realsense_r200_rgbd.test +++ /dev/null @@ -1,7 +0,0 @@ - - - - - - - diff --git a/realsense_camera/test/realsense_r200_stream_options_params.launch b/realsense_camera/test/realsense_r200_stream_options_params.launch deleted file mode 100644 index 4175ef4df7..0000000000 --- a/realsense_camera/test/realsense_r200_stream_options_params.launch +++ /dev/null @@ -1,43 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - From 2df7adc966ed80d2546748804f5e85490312d0eb Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Tue, 28 Jun 2016 16:29:07 -0700 Subject: [PATCH 121/124] Updated artifacts to disable native pointcloud by default Due to performance issues, native pointcloud has been disbaled by default. --- realsense_camera/README.md | 5 +++-- realsense_camera/include/constants.h | 2 +- realsense_camera/test/r200_nodelet_disable_color.test | 4 ++++ 3 files changed, 8 insertions(+), 3 deletions(-) diff --git a/realsense_camera/README.md b/realsense_camera/README.md index e4e6337f74..3d9d24055a 100644 --- a/realsense_camera/README.md +++ b/realsense_camera/README.md @@ -51,7 +51,7 @@ Depth camera camera/depth/camera_info Calibration data camera/depth/points (sensor_msgs/PointCloud2) - Registered XYZRGB point cloud. + Registered XYZRGB point cloud. By default, pointcloud is disabled. IR camera @@ -101,8 +101,9 @@ IR2 camera Specify the depth camera FPS enable_color (bool, default: true) Specify if to enable or not the color camera. - enable_pointcloud (bool, default: true) + enable_pointcloud (bool, default: false) Specify if to enable or not the point cloud camera. + By default, it is set to false due to performance issues. enable_tf (bool, default: true) Specify if to enable or not the transform frames. base_frame_id (string, default: camera_link) diff --git a/realsense_camera/include/constants.h b/realsense_camera/include/constants.h index 9ba4feeb65..917159e345 100644 --- a/realsense_camera/include/constants.h +++ b/realsense_camera/include/constants.h @@ -44,7 +44,7 @@ namespace realsense_camera const int COLOR_FPS = 60; const bool ENABLE_DEPTH = true; const bool ENABLE_COLOR = true; - const bool ENABLE_PC = true; + const bool ENABLE_PC = false; const bool ENABLE_TF = true; const rs_format DEPTH_FORMAT = RS_FORMAT_Z16; const rs_format COLOR_FORMAT = RS_FORMAT_RGB8; diff --git a/realsense_camera/test/r200_nodelet_disable_color.test b/realsense_camera/test/r200_nodelet_disable_color.test index bee6c68eca..5835f8e8ba 100644 --- a/realsense_camera/test/r200_nodelet_disable_color.test +++ b/realsense_camera/test/r200_nodelet_disable_color.test @@ -3,8 +3,12 @@ + + + From 66a6ea2897be36398d4bd233f1b4ae0937117df9 Mon Sep 17 00:00:00 2001 From: Reagan Lopez Date: Wed, 29 Jun 2016 13:53:33 -0700 Subject: [PATCH 122/124] Added navigation package changes related to camera package refactor --- .../launch/r200_nodelet_navigation.launch | 29 +++++++++++++++++++ .../navigation/turtlebot/README.md | 4 +-- .../robot_description/r200.launch.xml | 2 +- 3 files changed, 32 insertions(+), 3 deletions(-) create mode 100644 realsense_camera/launch/r200_nodelet_navigation.launch diff --git a/realsense_camera/launch/r200_nodelet_navigation.launch b/realsense_camera/launch/r200_nodelet_navigation.launch new file mode 100644 index 0000000000..6414d5e200 --- /dev/null +++ b/realsense_camera/launch/r200_nodelet_navigation.launch @@ -0,0 +1,29 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/realsense_camera/navigation/turtlebot/README.md b/realsense_camera/navigation/turtlebot/README.md index d44d6c12c7..1ae0a2d50e 100644 --- a/realsense_camera/navigation/turtlebot/README.md +++ b/realsense_camera/navigation/turtlebot/README.md @@ -39,13 +39,13 @@ alias setkinect='export TURTLEBOT_3D_SENSOR=kinect && export TURTLEBOT_STACKS=he ## B - Mapping -The only difference from the kinect version of the navigation stack is that you need to start the camera driver before the navigation: `roslaunch realsense_camera realsense_r200_navigation.launch`. +The only difference from the kinect version of the navigation stack is that you need to start the camera driver before the navigation: `roslaunch realsense_camera r200_nodelet_navigation.launch`. So, the normal flow would be : ```bash roslaunch turtlebot_bringup minimal.launch -roslaunch realsense_camera realsense_r200_navigation.launch +roslaunch realsense_camera r200_nodelet_navigation.launch roslaunch realsense_navigation gmapping.launch roslaunch turtlebot_rviz_launchers view_navigation.launch ``` diff --git a/realsense_camera/navigation/turtlebot/robot_description/r200.launch.xml b/realsense_camera/navigation/turtlebot/robot_description/r200.launch.xml index 1e764e3c03..85814d0d1d 100644 --- a/realsense_camera/navigation/turtlebot/robot_description/r200.launch.xml +++ b/realsense_camera/navigation/turtlebot/robot_description/r200.launch.xml @@ -31,5 +31,5 @@ - + From 2353eb4c9b4fded638c32bff33015d5beaa43067 Mon Sep 17 00:00:00 2001 From: Mark D Horn Date: Thu, 30 Jun 2016 18:20:50 -0700 Subject: [PATCH 123/124] Update for ROS librealsense Package Release Migrate package.xml to format 2. Update the package dependencies. --- realsense_camera/CMakeLists.txt | 14 +++++++-- realsense_camera/package.xml | 50 +++++++++++++++------------------ 2 files changed, 35 insertions(+), 29 deletions(-) diff --git a/realsense_camera/CMakeLists.txt b/realsense_camera/CMakeLists.txt index c748806a6d..4a90135bc9 100644 --- a/realsense_camera/CMakeLists.txt +++ b/realsense_camera/CMakeLists.txt @@ -14,6 +14,10 @@ set(CMAKE_EXE_LINKER_FLAGS "-pie -z noexecstack -z relro -z now") # Flags shared libraries set(CMAKE_SHARED_LINKER_FLAGS "-z noexecstack -z relro -z now") +find_library(REALSENSE_LIB realsense) + +# This is optional until the first release of librealsense as a ROS package +find_package(catkin OPTIONAL_COMPONENTS librealsense) find_package(catkin REQUIRED COMPONENTS dynamic_reconfigure roscpp @@ -55,6 +59,8 @@ generate_dynamic_reconfigure_options( # DEPENDS: system dependencies of this project that dependent projects also need catkin_package( INCLUDE_DIRS include + CATKIN_DEPENDS librealsense std_msgs message_runtime sensor_msgs + LIBRARIES ${PROJECT_NAME}_nodelet ) # Specify additional locations of header files @@ -66,9 +72,11 @@ include_directories( add_library(${PROJECT_NAME}_nodelet src/base_nodelet.cpp src/r200_nodelet.cpp) target_link_libraries(${PROJECT_NAME}_nodelet ${catkin_LIBRARIES} - realsense + # This should be removed once librealsense is a required component + ${REALSENSE_LIB} ) add_dependencies(${PROJECT_NAME}_nodelet ${PROJECT_NAME}_generate_messages_cpp ${PROJECT_NAME}_gencfg) +add_dependencies(${PROJECT_NAME}_nodelet ${catkin_EXPORTED_TARGETS}) add_executable(tests_camera_core test/camera_core.cpp) target_link_libraries(tests_camera_core @@ -76,6 +84,7 @@ target_link_libraries(tests_camera_core ${GTEST_LIBRARIES} ) add_dependencies(tests_camera_core ${PROJECT_NAME}_generate_messages_cpp ${PROJECT_NAME}_gencfg) +add_dependencies(tests_camera_core ${catkin_EXPORTED_TARGETS}) add_executable(tests_rgbd_topics test/rgbd_topics.cpp) target_link_libraries(tests_rgbd_topics @@ -83,6 +92,7 @@ target_link_libraries(tests_rgbd_topics ${GTEST_LIBRARIES} ) add_dependencies(tests_rgbd_topics ${PROJECT_NAME}_generate_messages_cpp) +add_dependencies(tests_rgbd_topics ${catkin_EXPORTED_TARGETS}) # Install nodelet library install(TARGETS ${PROJECT_NAME}_nodelet LIBRARY @@ -105,6 +115,6 @@ install(DIRECTORY rviz/ ) # Install xml files -install(FILES package.xml nodelet_plugins.xml +install(FILES nodelet_plugins.xml DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} ) diff --git a/realsense_camera/package.xml b/realsense_camera/package.xml index b254b4d421..39225f7fed 100644 --- a/realsense_camera/package.xml +++ b/realsense_camera/package.xml @@ -1,11 +1,12 @@ - + realsense_camera 1.1.0 RealSense Camera package allowing access to Intel 3D cameras and advanced modules Rajvi Jingar Reagan Lopez + Mark Horn BSD 3-clause. See license attached @@ -16,32 +17,27 @@ Matt Hansen catkin - roscpp - nodelet - cv_bridge - image_transport - camera_info_manager - tf - message_generation - std_msgs - sensor_msgs - rostest - pcl_ros - dynamic_reconfigure - - roscpp - nodelet - cv_bridge - image_transport - camera_info_manager - tf - message_generation - std_msgs - sensor_msgs - rostest - pcl_ros - dynamic_reconfigure - rgbd_launch + + message_runtime + + roscpp + rostest + nodelet + cv_bridge + image_transport + camera_info_manager + tf + message_generation + std_msgs + sensor_msgs + pcl_ros + dynamic_reconfigure + + rgbd_launch + + librealsense + librealsense + librealsense From 3035e9c0a975f10ecf71b0995fabb45e72f8826b Mon Sep 17 00:00:00 2001 From: Mark D Horn Date: Wed, 13 Jul 2016 16:59:10 -0700 Subject: [PATCH 124/124] 1.2.1 --- realsense_camera/CHANGELOG.rst | 5 +++++ realsense_camera/package.xml | 2 +- 2 files changed, 6 insertions(+), 1 deletion(-) diff --git a/realsense_camera/CHANGELOG.rst b/realsense_camera/CHANGELOG.rst index c210c91061..3adea94727 100644 --- a/realsense_camera/CHANGELOG.rst +++ b/realsense_camera/CHANGELOG.rst @@ -2,6 +2,11 @@ Changelog for package realsense_camera ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.2.1 (2016-07-13) +------------------ +* Fix starting /camera/get_settings Service +* Correct ROS Dependencies Install command + 1.2.0 (2016-06-30) ------------------ * Update for ROS librealsense Package Release diff --git a/realsense_camera/package.xml b/realsense_camera/package.xml index 8fec33a31b..9887c2c27b 100644 --- a/realsense_camera/package.xml +++ b/realsense_camera/package.xml @@ -1,7 +1,7 @@ realsense_camera - 1.2.0 + 1.2.1 RealSense Camera package allowing access to Intel 3D cameras and advanced modules Rajvi Jingar

`Bv-RS}sg`T?tj!V8in(BvNMimON;R7a?H1Q(9I85PE6xXz6OxeNJTciwi z4ZcSv?J`X85_jppT-$}%>CSx~i-ty&TPC8u(ZQeoTR(kpM%TCM5h73c^CN!PC@G;u zUsx0CA zpJ+pXp`4VRN=Lb_HMYKkogLA<9HB9`)_Qt|-6IpR>;z2&96aU-8OU$gPGadTj5+JW z2mb&F&x{5~>IreQ;!CU2o34Fz3#!+nkbo3Y$P-t5lpZq&F(Su)Gz#)(Ib=kRZzt+oZk#99>4@)1-U zG)hWa{iy5zzI|U;(9d9gGx<=Ib^sC=pn2v&X*3w8m`9C|9&8+9cc-O7ZAJ=pXXha5 zWbfU8aiKrg(p+!|ASOxCrsT3k>HQeEq9e`@0^uS!?LP)?VzR1ne=6L+nud`2eH2D0oGk?GA@nu%|EfDGzQeuC;kyA;g4Q`?bH$Yd(*%N&y_g%8W(R zaf&{6Xozp)d)i~CiQ~2_$WxP`&O5}~%p?CcD27hdU#o5cHB>`D>pC=o53?wS-t!bY zkg&o2Ja)%%$bJ7ASp-K{;&_DNgx$QytIE|7IZYW46->^OOFJQXaYgD=(kQ9T9w!;0 zz4_&PZoh^eM6g@K`&}0$dYFEyOW82x;iun16CqD&wmH1Vtav`YX83&WqN{+x;(15L z$@)p?0gz=KC$u$n&s_Q`S3L0_e}k$qN{6*yoq`KV4>$?T3t=e`)P0lH2xI`+y{xR0 ztth@KlZIa0k7Ro-AFH(3&8}xee;BaqtzV?{P3>lSB^Ky-0Y6ix9KplUBU3;7VpC@f z@p~@vo4zRyh~l+7rx5ao5=C9S56{oRN1nuVIFoSFrzv{bHoT30V}$l8^I9Q6Ej&si zq>_`qUX0$$t&-Ad2R3 zYxWG!Dxx@v5BU*iScKUDXp=pq#wnFZr5I5}HLZrTkAIoYK-eBDGU%F^6oaX;)C0Q41Gj{jIt3bc5k9 za__2BCT$10pTkq2ME-28&k?a0%-V{NH|K&PoySAkOs2K1;<8z4kgzj_;-47UA2fT; ziGhn|eCZLJm?{pNL+0lTq`{lLzUJ>;SG=%Kj@!)iervUVjY75bGRWrd@5nM^S!NPn2%EUY>vshNOSfmseG#t z8$)VS48mUX#6uPHdIh9&ajWMKWw^k1d46D=i10D%uh75!ts15q%+~!_EPK%ALm(t* zkK<>C@bg^d<5Nh%wk11$0L-PkQ`d_la9-~=vmEL$i9RNzPeEG>!*+2V!0DSBBvvJc zF>1axJKm{vuRWxxB0oqx0jUxHWwe=C!cwWHCYtHwV%d=ZKMqX_;I5+9FUHGW~Ul!;s8Gc0o3zF?aS zT`C;o%({~d@->Vdtxj`Cq{fk>^QsGUnvr-P1xD7s(Usb(Zu=9IZQb&@?rZuOA60nr zOEXt+B22t~e`~r3$=xFcB*5((gBs`V z2Rz8wad;kMO~Gp3S}Fnbmh^jj7jXAdE$C&!u^J#AO9#!w8K(IB;+ zoa0?gg)PkGr0{iPtzPSWzad0#W)>&E z%`Gm<#i=cC)c*!WYYd`UA|N$|-3AW0LO}}t@9{mO1)1U+Xx@H~RwwD6 zE(Js;9VH$SoXl3}LrsKGgugCb^t1&$`aZV1i`Sq?*8{Ee7klv=4X*nODXz^XUl3Cg z+n5KD}^-(;Z%1E59Bh*aH$m@dvE-#6c!Cm2UIOSE({TyC3kv6Mu3e~s? z-MR*T7dZEQLoS6bbrD5ka6Syhl+|1hRDhV>2VQE%#? z#-b)@N+}34jfx^o%FOA|y#8lvL*Op;&1&mw&2thCKJLi04tzkHP93W);B?lOXh%N< zYgMrY*Oa2|i*y3Tvc4^X?l58$^ml}@y%p7)rn7K%L+!9>L!0x^1vv*Q8D%}5nf$Ka zZxtqw{-wY1Z@1>gEsP7kqOBFwEXP$&O0FqE_xxI=zJBpnr><*m_>zz!*3WX{UfNly z$DsvEe!uVM{KxW_5g@EAql~PHa+f(vVqCJB#yBMWV^ghq3%T-2-pxaG3&(kIR>!U@&K^q12((ir6&pw$qT10)` z7}qQpjuE_Nj-SE;8Q7HJ5Gx6uXu&pA(=%9qdm7S)dTTwsFA|#%zw@*#5l#4`u2HAk zPrXoJmdKFseW&;W>>$J@AH&SWE>g6%=KBPg)2&h;u&}W3XkH%~8Tn}bUFYWJ08Vc^ z%Pgf;`4E~S-vwaje3cGg!`RbM$IbHYVz3*;Fmu~n<3qqZ>#Et;XEsG`-&f2hUn@KV|=U~ zlFaO7=sMe@{F7$gw_~VPAC!B8miHj|cu^{9EmA+$+1XC+;i3|4=be2|q#1=nlCZo$ z<_n+m#ZSm4(g*Wh$&YleVz3IfE{5}>+k$c1x`-13Ni(iGHay_g#&E{&TP1&Cqk4^U zo=@-RKmC%cJC~9@*jutSBmBd-7ru+Ayf&2dED16e-tGiTmxd_I1 z`svRf)muyLfItn2CAWUqZ1*(N{^m7VqfWx+Wa%F2s;UOc$uC2!yF5I!)$nA*^3*UW z3zR5}DgTo{Y!z2XW1tmZtxJ#U$_bLij=f!&!^SR6Iy zBQ@Aa-G1N`gG`Zbhin}e?pk5=r6Hvn=#4h7BBbO;uR2>)y>$HLo=t1r_;c-0?wt+gK$6LYt~h^+qWbuNs-DBNdsOC7DO1Yt-i$mD!WJZ&Z?^^TlG!&uMl|tL z){T!-Qm~WgdoGANSiYgNk&!N>c4O5EwZbz$Txf!=%+_^01LZ=Y%v?Xb4}k1ym_c?X zwyHLh|4~FP{_i#}__m>^+{=0E5kRpfR>z%TegXlNX_jIx)WYe7 z1!{f6$2mm@X_4JXA$F@(_(n!X;q-)SwfpC8QK(SD9wpoBgF`C}O(Z6bS^Q)sum`CO zhuN|D`}u7E@VBrjc;D|NMffpKWj~P%RaIU_+6XsewZ#U&uFL3IWBj)d*7E5|X~rZT zkP{}%B@Q+Komv?vWma%A+cDh?P~b+sdKbfa;z#%s4r`RvNP z$MQg48jz|E+NXUz*}P9wC#FjlPv~9qR6`b0T-3c!4tU z1uYP=e&DqdK4-Xn8sPQ0K1OP;n7@saWa{n1hHVh+#H2(g#Y&X?WZhV8!P2niqNAs$ z7GgnvupO6F5@jU%QGrvbJSgRkPVjJ#cK(S6*2_zDJL@OUJU`YhlaYbIQDkpSk9Q5VWBZl>@x#{5e?y(u0m~t(`^2#S^@3E7h@{Y(7g$9+MG<*&MTigN zY(z<+u4`=if&&PI>2Ek5AB`0tjbG1==!?3`4C3pk8FiGD)4bk zo%!~L!FE}{|0vnf(MZ&xq4nd$Y2oKC1nZ3gG+Ixr6Zm*;MgQ7?7-&(L-qrZ2)JDwJ ztL%f}P<=_N6W4Y%VqRE#cJuAo$9aOkKG@{3}pT(`wXg4Gap;?Cy`~L@@RJcfLYFh&R8-G z+L-j{&HTQ3BsIJs(?5>{h;q;&TxnV1(g6aVMPk^26g_{9&anmnfb_tJArfq2;N6Wo`y0dBx&!Fy@FxqcjUE(JvC)i%+RHiE{D;xX!L+e5D z#Y21Z?+$xbf0H-uHFba5IGV3~Z1}!${B@pOSFbOOOO*Vu+&;PF2MsT0n&{`rS!%WM z4`?+%hHt+s@5hoUX5~h>oJrbL8F$jUD#*kGEhy!aYf{WDHjJKysTO~8ZqHko$4+Q0 z>IcAkKyaDRZ$b#q`|KMoWy-MHJUAHS+Bs~E`HUv5AOu?@J*|9W)qR4jpSZ%^_yRX@ zp(?V!KeubKE-491qd@fIXbms*%(lyXe;^BvNQIEujumia{e^$!gVu(>dx_2h(bKXk zbWz%(e^R_SpwI8|*Lq~9bU)loTpi@b@Om|`Qw@6v5sA`Ce^ZKu(5XJkXj8B`{jq3O z@^&ws-ZzT%>*76B!Vq-^elV$!3>hGNigOM`bCl`wCYovId&5&5L$XVL8y9eGuXWmJ zVPn;8ItAAbN^~+t34=WTDfNh=7dFf)wtf0Qv|b~Y4s&E~mzs9>>LnMOAm6Ies=PCC zj!=vtrflxt>O8$*Wd?{l$F+zqnVC%T*&Q7Ac13FImvgw10lwBZ$or*)>shntrP;hW zhr4%og52nw`i9CZ3TG;?{Y41yU&^96i{-9nV?!(7JqsbB=|sWP>!RT}Mm^t%K|aUg z@+RA_8$K;3!-={VGLuOCD1eD-XG{U@OLsPu)rSd-U=Wc~pJ(WO6hbdH9H*{PH#cVy zJB<5IptZFqw3sQF-5;*8dP8BMeNp}ggp}XkDOoUIdFSu$p_{d*XJGKFFmtdMaXCwu z0n`!5%e-R#gM>(N7B24hIz`~P*dUELN~YPRuVc0C+9FF)hGU-pi$To>aIfVHPVxNE zcQ^(*BY%QYaTLXn`tP&HIlNB3-XC3C4!YfajvL!x)u=Rcaq4Bia^7teGkU9_GBi%u z1E#pe^;aw{RpHuC;B5@e;PDRf&N&SZ%L+$W1z*`?aftJP|6fOuLtY z*|*wgGj2cgZs5~>pSkjKm@C6^igz-*O{I3B1dlIup-wDB_RfX6>k1Q=ATTcEew;a1 zc%)u9JChNwO>le(*s$>`#gl9fo!@VZJOlomvgla0xIy7?%wa_}iSXJK2S|MhfxKc~ z-9wZ5haRvQPsE8>s#ZV{xfaq%dS7#kT#4epd7TP@+Zm~3p{?cqVN|;+%CWRcKD{h7 z3Yz<^zo$Aa>Y#n1PS|-DL*K1jA%pzzdFlsU-A8J&g>l7p2x?qnu9UK(fljwI!p=z? z2U!3`4ALYGRP7`9%*c`Lpn_*g^GEmWaF*%b@`!8TL{z`|c31}Fgfd>`SpwoM{t*`T z@&XW8iM_zK}zN>?X1oxIOo?`q4xMSGn(jB>RpuPwvX|3f zysf2<<|dj!K}?*%SN7SS&!4W)HFIUH^I`umF7OBzw>!L!b)GGLhJ=LlLYfN$5?KSY zi-&+o-A~7K{+EDGvKaumA+OxkURA&x;9aM1!qmx&@&{Ts^Vy7p#gLp*`c_QS=#J;% zUTu|EciXH)v(*V_*Wdks;It7)@(le zamU6wpu$S4o*dE8Ts^e?_)5X1(AI zZD@R7SIei|yIf@9n#_vX3;T{Y=W~6JKd*;_lFqcUa!n~~+(c8tZgM}QTr*Xk=nYoc z?MC|$6B5i7xgqd5_q<)PG)cVY*ZT8b7;urIW4gvz*j&Li%JD(5<_RueYvqz3#)4zq zK3bHJgJB?$Rpcwk-B4~8u~3r^$2?6$s!Y#K6D6EtnCB4Dw^#Tu>6e`o%yJD;?-R!l z$O=mS_2BfRzixB7VIe$p+o1CA9xzm1%_nytLygstd?6rSa0|&|s^>$GAEpWiv~u^>{fZ%gA7+`k_DFoi ze@mSg>`TRF6o8nTWNW$G>ZR9VMrR;6BXJgvm%&BZ-cncC7fMIiuFc|8KlK~t=do$1 z`FEKEp8&}AdB_3ZjMcozfNd6e*@>Fppg1WaYQie=e9Xj-VB=SmtEe@J$Z6ix+-yo9 zh54pyQQ`F_r9O0TEwwG1hp-jpT-4a&SX0OS+RlM0q&i=0MvF#_=L6iRZZoItS4+?! zYwh1_GphNpoIKv(WANwno5y2C+B0r<(KTLDzM)PfEO+|%_=}P=Zmc}yi@jE00_vf8 zdHUy;E3!0)dpFZ6i^Hz{V9yat1&wksA)o^W{xVaG-zHj3UKb)3ziorl^sDil1({g} zF}syA0+Km6xXTf+sjUyT(I<1h+DS>(GYp~*_LTDOa1!eK$Qq%{FsiP&g(C9L@Q*@N zR21CW`W@cG5D0n{h{U2yEGyf(rT#;}o5Lp?_C{se{XjQU&oF-9_Ke1)&)avqb|XUy z1kJkVm2JF|m^Y~Auo^`5`C&9zG-Ur+Nv|_M-L4-vS7m_VC5%1$78uKMX?eP$n&|%N?WB9dGReUJ>@PeNz;$o8_n-Vyxp0f{D8zS7QM~1nJ>| z0Asx9OMw;ri=_fQ4|}>=4-QEA;X{{wMHjxWa*i6HzcT3@5&~AB*P^6ZjE=x{fhcPWU-znpGEgWwG4^FMs!5m^@<>uyc z0MCpd%gX@G*cb?rs*95vJud;%Nr93KnB4>vEO*ZK{F?PnYB;BO-gbRk&?-7cH7fFH zH2>y=LnoLMdv&>4`buY&W7~>m8J1eK(^`&7O+4ZW?+`h0+sRl^yOq{;kK-HH^51S4 ze-=J7VmmZxLku7zSC?R(L~jY`wuXz>QZH^f*j2e?e*!00YBOz=CHC#Gt*SS-+k^gY z;M)X(If6ua&N`~p+#$k;nhiBa6Np)CKioSKy;jLU{*vqmX&csy2(~*Gx_v}>SVC}mZIu@4r;GO3p%GDMz2EIl)LpAQ3 zyl9Dtf~x7ef;}RjC-&0I{OkMq88gN>NhwDh5<{eM=U2_m!qsh4;Np@d)>4 zIjU!M!hWTrAQk@gn@ zQJd$xpeK9$L0+z16KPamEcgS~`9*%kvLd)9>Dv4izY~@NSm!eL8{WKJfQ7a8^hr~y zj9pV(2cx!p8O?}y%Xt!HmUSTha9nC`UfW5uGL_m@sO!$;e0)_iqM!X;Zgs@&%s7P7 zyScu1gP?Kq@b`@QTW)S_2?kY}uviy6tu>@^J^ND~V%C-RDM%x3z=&|)td7AE-00h7 zRR|pTz(+<#mYkbAcK%Al{{}tG4?}WiF$J1%HL!ay3hsdMk;s$QeLPIitu?uzfB!z3 zeMPiO2@#m)#in(oJ5LBL6)MyB-|=s2c^I$XH>&k{OYa&Z9eTuDaWydV8&Mn_JWBal zY^8|u%PU?#ujS=DfXj&SzKqD@9uGv~YiZYu74yex|)6uW`IcDF5$;Q#<4JCm?w(gA?^-Ltz z(0Sj3Nx?yxJosDftCn`3mrRd+54AOS^h%V5sG{fK?GHKh+8McU!-I(00?Hu0m%xhx zAOpnX8X^7J_f2`sa4%6FS}a{W#S9YA<$>nF`aRgNP`CCFgB!qI)}l$Hx3Px?l=;iN z7=TkaX>6vl_)!K|RI6+wdNoxnBEkORS;N)N3Ozy+69e%4PgU*R33Dm7kK^n8q%cKw zHsUvC@c9*Ib=Odhf-FSL?0q8NpU_oPt&pP`E6?nb?sh5Csfn)-{OXBv>(>JZ%z1Ur zi*`N-_39(2M)%I-K}*5-Au%WGTrtQWf_UCC+cZaoNr&~f34;R0U5o9^Hz{Pi9iV;%8^K3@*8mThEuL2Q*J zad&*zuK1OFoJ4|hu1Ywh6(toS2VSzVir5y(+agc*&n^jlwx5UKOvpaHUT@9@1LJcp z*zYGbqCHvnm(8EdJ81Ill~;s*+p(#Qfqor&Ah#&Ye-NAWxObP#i z>tE)>c>_CL<={|Qlt<#f+}{6TDQlpq|Bnd3Kj(Ao|L`2(u7j`t{~vrzb$e&HH{RD& z`q>{Pw82aoH7Vw)PLZy&vMrKhH~ zT2N1hlwXl0v-!PT2ghdHEUNaw&#O6iaHAzcB+#)ur&OCUKq!E~`?cG?Qzg#DA_tGF zFe(3xXFZZVn75fc8|#G>$H837JKHYTV2bdx#Tqp8b7)`BmxYMf_6sv2%wiJ~bg*Q= z-{IAD4*kfWOc%cM@jpZb3$0RB@*gE7=9fFekOq5AYAo@L?xj*fhTsPzKIdnOb#ynG zZb|^?@-rfsyXOB{0_$1XHXK6NMJP0zR-yuv^z}NuG167-5xly!SK@GH{MBQ|H&+im z0y=_d`Ch>21&i^$J@j#I((;ERb)y1TA0r4fGb~qOj?mK|Y;I|nsi@Q~|9KTZhz<`A zd*%Q`h7IlBs2aq zVY*O4)06BTpJ9Pu`!1_3+IH9|$A`S@kr=Twgc*7bO|;Xf70c!+M21OzZy3kvu%vB0V!R`pcJB z0)m3(XDcmr&CP^AcjOY2>q$8*?bJM-R>@d}6Z+0RePkLfZ8mU1XXIC+f|o)LA91`1 zC)0Gw7U$9ib}hcg_FOw(aU9J~*v+;hFJa!}s1=6BpIb17<3+%!L=wy*FI}yH`!&$` ze+6dp_j1D_IUgOafb&(^Spw(qqDQaeg#@fW3JMBvyfalR@SIKAmwWfBnuyC2rGNFO zg~eh;-SnHyb6F z28nzL*?ej$+G>5$)02yZ1~U|%XUjL_3*dJI<`z-t5>Ui)tKIa@<<5%a6Mb zCUtY;(x^-{|5dL@rB_NfTWYZ9;M{Ec1{nX{@&PcB1bSHP1Mk65)hJM?c&?7Nk>4%z z40NY6psw(sI6ilV3j^7|_Z@8@t?KMg0fN4X- z+8uAEmb(GqsJ0v%^WK9L zxE_J<_tW-G^DL0Gq`dj`|A?3T7-MGL_sL)w=`P^(`7JTG+<-D$L5ybkmRd$)-{*hC zSze>H3&9x{x$WVGut4|y8F9TXPeREP!(u5J_)zSz>pyAtN7d{Ps{V6y@2dPbrgwvu zm$}to%W1d?E@_;DY_A9$x9f|@agG4>m{NHt`}9V^#L6p!+1UyTLU-txMB~lJ&u^L zl~FY}8s5A@v;0@k$(zqrXanHokWVF41%7=E-1j~i8s+8X2TP62pE-q~G^vJ|; zjbJ_}2o-utZ=n!#=nuNW0N?oISrpQsdj%o|w6G=pY4tpO@_GH9nOOu~-Hj3a?olOv zwpzc3ZLEz&(~x(J;W*avxDSTL`A^kiaMdPdW#w>Cgxr7cNZcdL$(a%g#8J)@!gpM# z!ikhO|CEQ10H?dMaCklXRNZZ&nA0(#JJ`y|dFgm+*&+)Ek`M{up`sy5)2xEqkH#ml z>}Fm&iND6q05RXW^(==zRsZ~FBUOoI_L&`+|JT1&Y|$+J(&St(2@GoQKse*#p3Hws z3;*OB8eY3X`P6qAz$P&hOGW*6$LWT0XgnT4WBvDHA!eb9`cU_thvKAg1PPPtpS4(8 zwU{eUZZ-N!@T2)_IEP1zgO?XSKc)9O{JWZfe_iCiKh%|g5M`z1$`3kGyA}}e&xR^* ze^r3KM#yHgF&VctG2k-$6N85&frH)^p7HfM0|do`VP~rs+ezY*)j9x81$Vnqa&fuX z@T01OB|b+65!wiu)2f5AiP*%Wlktf>qzWyB+}v=S(8r^MfA;2YVlTsSm3bn*xa#Wa z*fG+ORxf7NJR#%@(wdLIJP$QQd@o;f+fM9A-F~H4nriW|MJMG`&ZJc`XRBdI9ll*o zOnG5D<70x))qAm-+MO#}DM-=tH+3{~bUYOUuoi3IG`Ci#PUQLPz_)OLmZj48` zFf%hhr#u4Pi-g6*@_S(qlK%ulq;|#YDiaLPV}|(mua@ycvWT(C&;^76w4<-!DJ*#= zIuywHUKt86>G^ENGU0Kh`jI9Dx=lkvGu0Iw?6lrV&c?>}2u4RnK93L9IuKibF*YLI zIMckZY0ho)IwpY6Nf^;n_;EvF)p3OCNtpcXxc_}qciS$MI-u`oBIheFR_*0$V5wQ% zn%B#WII`am{#kA%ILPM~pE5VbRSdg=L@~((sN$!u4LqWZKc`#jkx8_+xCiwaFP!eU7VhQd~+}>4^J0&bp}F=i zQsXUs`IoKWrF2$9C~Q5rxQtM@SZZ9sy%E7BYG7eOhls|Nj?97LY75zEbtOFI2S?ez zG73Dg>?VwMV~`?VT&%2egs1$0zZwh6o}Y&k7{OBF66KQr$bl%*3e7!|(=jq$buGX{ z_p)!rqsFZnEiN%}aO0&BNV%b|eMs89PWKVl?_5Q~&oz`P6vO?r^(GP@U#35{=KFW5 zrpCHpe^*BdLgXK`Dy`q9Bt9O7V=Bl$t;5!YIl{j&0q-BKvWBv_Q>_F%Z1;lp1NMda z*W>3ab#q{x99v>pu3b+}e{O~-gExwk#JFHr6O^8DuTzhS@F%O+>UugE@@L%lM6a`8 zbGFFa(w`^ukx^E)w7Rs*5$7t06yCH+NJ~q8U_d&DKmDBYjoQxp3Str1`8p+VJ&=E) z#@O-aH*P9%zrSTqc4iyhA$Cg*OmDC#;)|rBzQel#Hg0U2uJ?ZrZTR|3SpcNgeq}<< zi+-MGPNwhF4h63A@5lU)>O(o9VlblzS%lbQ{^~0NoVS#m#6G5OJ;<3tUKPGsT-GC? zmuBZ>0$#@j5${!cK|$gq@n?a-L~=(R{;u=R2Q(EGLL3~N3tb%o=(4K}%G!YX1}hD& z7@laX&-+mUz{vP`qiamG&;FW!i2L>lDee{cCi}r-u}U9W;_Y1MX-~CYQ(|Jjh^f~) z*GWx7LtWBs_}F{&bI}+`PQvG8mrM0+(7rS;^5MK|oh5neY{Ae~ro->L&Tg6}*L{%K zX8IcetHH*yYgZ$s`^uteaDvTvc2?FK=cNYDdi2b-^;%Q$2OJK~XEniHyoUw%N8t{C zSd%M$yyIX0o0Ay$!q0KM74|v`hd6OF6`@PTmMguu#}C>mu6QcTb8F z25eGci2sVOO_ju7bcF*GmYe?YOH0%J!1IYSC5q;P1YM2ubGmOyb3<~uZ86!}p^^_c zL!3li7lWkZul&X`IqlXvMQggA{XCpI0L)|SZhaUwpPu1+z}99Ih{w^#VspE++{jhVW)kv|le6-X4|~z$GhX9w-3J zkjXq@Sor7{1f;QtTUS&%Ox0*$Hm`%#zoWxMB9PCOB01ls`p+(b`seR@A`{P#@8FxM z*hEbPxt&29l?NV!Wba*=AImcisw<;OR(N_O3<>II~Y{dh-^Hph#hF#Y* zu#uR9`_?3zy(?jUXWe(7+@p5FV?q#xGWZch{5$C733fyK#Wvsf4IFLH)$Fi+Zi6Gd z))n~R4SyWF_?KAkt5$dK_6zs{M|r?CUxDMQ`mv3C$6GiA-~|Hzcif9z&-ayg=a$KN z!4K?kg|ZT*3`@eF#oS-^`Mh2p_r*`;kRzMcE==Y}(oP+>n8tGE?;MZ41Q7l&vfer>%C2o6mTpv#Zd6cd1{fNH z@D>D>?q-l0VCWiB8bp*16QoO+p}S#*ZiW~_B!-dh@8Y@N_j%WEeY2K-xL9+s+1K9t zJdfi%j&lole9||2i}BhR`tmH~?P}BVgj<$xnR#>53A>N)=|;YmU(;B=7S~5X!;vQ4 zUoSJImj3pOfXS%Md{-HOe*GPk4I*_>x<5l6YHz7VzskpO0|e*rQenxV8%s5wX#<|^|VSo501n4EpK<~IyJu~FeU z*Q?=2-+&YC*pIXyL!2jTnb6%S>%?^btg0JE-3c78f4pEg!_YIN5~4oJpoDQV)%`9q zF2D~CCDq@&8KLkmsTcJTafk<#kw`%?aa=*i1e0d|LV#J#0rit94|%ZMk$&n}TH8h4 z1iw6iRFNBtuHfh&ViM--|K|k*Lj>8~&>&v+GbP20<`GO!A7)#{bYkN|5Y4?Nz)-tO zsE&;oZYObTFA4?yqooDbuAXPm`5qTTWkpX%2c$sj^b-N2%bl@<5-#4w;;0*e2xIPQ zZ=4y-+4uE`!PAMw%Pg7E3t(CL-?3o|->ik8bDT-%0bpKfOq4i2)hU-f^Q)pPI^QG9 zR|KBx_HMSC354(#SNv0MpX6yQSmBjbF~nIEe49?O7&~ z=JU#0mC5h_Bo9!o2$t%-54CHUUc;aYe*;;$=;Vt;HZW~&;9Tv_TCF7YZ%7o6>jR(XuRxIMh30fx<4d;D88s8dRef>%e(X> z1aTbkgg*?Y#uYd=mlFGSj=E(J>*W3f)ORv#xScf{0PJH*eG|6`ma*o;8ArRt!QknL z$=bZEjrjof*l%uY>Ha?JS8_XubQCJE^#n$}!{xhj8|ExES;(}1{LzbD<|-APjZkyPQhZ|9so7l??l&5gH~E(y`SRsx@ot!9YZRddU-u?zBPgB%2u6Q zEZW0)rfO#?(7sP)pIM+3A|}v4w8BwZCpzeC8w`rb*6peF$^gx}vs1N4d)L+6-1^5* z;yOz>QUopY-W9EcPO(ac;?qe7GHk)m2RI;_&iB{;X?{3vqI^&O!EQ=<8=+(Ih^$4+ z4bY+;rN94OgABz$zoEhiHOie#Va&tLcIp?!qrmg@b1R&PiEuEK7?iVp--;C5pmn_{ zWnK?w$!~yvWB~h^j08icXRs32Ib8!?NEjHXvM)O)j8tU)tYiwE$bi2qwfo8@hILPqjewwF`{fx;nfkysgBh* zl5}?XH>h!*3G#PS7Veedyz)IU-PhlpcA;&Me(l~i8iZW{P6FVIGnxaIGnyJP->h2< z6BW9I*0p>TQ3m{l&1GR@0TXheG{Gp@Y2Zd6Nrn|poT=7r{FbMhW$Z$XGbrF1A5EsUL>_KvVHm%U}Liku=r=-!p zBpHIW6_hBCAx#R(a#L^)BW?MSN~k$uzk<7%Yz}4+2=0pCR%JWeYCL*jF_8B4NK-L@ z`KJzrK^31*L`|EnU|>$;E@8R*{oU16uP`q8Z7}B*J9*tzP(4s>+ht60{oXRG1^7L| zni&gi?|GiRsW)5`mkmX}edX*b1Qp0v(orU{qB4g1@ z$DIM1x_cpQT+e7fN;-uoTjYgY{+?$;uCacG!|PkS6wfZt6n`2qFe}cv2r8p zcdSlwSIwjN!$Y0#To4sq#v>-kt$d9NDAF<)kF>`2qspzGcn8)u| zSyrib^S|EG16SRPS$9$I)e!3y=cm(aSu_?#Punt?e}8>$4Xx zVgiM{eA#^R%VR!;nS>xN7^7Y!1!M`CIbAeABip>v#M)Swnejs@q+oV2hImCx7Oeg?sJ^ppdgr`qF~ago_5S|; zQ%Dc4Zc|u(f9Tno?Htn0j^K_SSG*m`kBlR6)C08qp2pt7!h|%vZN(kE_qkm(E_)~2 zh=qXzhk(F7AaA4+M&1xG5T6>nx&(|`@2OKscf|m-(wYfv@)bPxemhmp<5IW57qHt( zWoTDfW-)0b@?r`D!aj<5@Rq()Z21N;Zp7rcXf$&p#Wq$I^}>|_Kfj;Mn;Tb zmEAN#uwl@PNim4$=%M)Tf^u>^=&)Td(aAcS@F-b~)B7Y*34=332P>f$unF+)-1T+3 zo^=HLD#bbk!H>q3<1^$=&XHZ2+TTD<>SQ9>qfJx#q7gy3Kv(J(J_ne_9lj zPkl#ywCDEjUScqfCub$IOJndm#gnPshSEw(`KM6)^1<(E(CU;X`K6-L zcIDNxP@xkTCk zpcwm=CqdlJ514o3Ipii>DmsjGVWs%X{ZXxW`oVa+#lXVbBrkIn=cOxtzr`%ndqay2 ztGed$;u%(obP7TN0K%}hHVEQE^Llm!HSCY5y8!?%vy6ghBh}2W*96uKFkoXv`se_5 z?F$+Ew%~N#Ro?|5ogNU`WJ0RN#-~%5^qV*OdCH%xB-`a8?1u?G|BO{|SsGT_MEkPu zs$X?7nRlSFq~-Vv+qK^zJZKth*jf) z-L__E=%kROnR1F4|FZd8H#7urQ^TymZq9GJ6PtrBieveun|eON^vv`JQNIsSaxGd) z42^>(+^$N#dee}&Z9vHL`L!&Z)EUrw8o-jDJ@I!2KyF-xgPxRZcv~pSA@qVvT-pH1AKnk_;L8?HA9m!K9D@mNZcI zpyxlDno^K&5LDJ%#RRXdsStl$<7C#bUGRYCDs_sCe}ljRq12_5E-juZEJU7+80nSU z3MMl&0pXVh6cj`m@x&>c_Zp}9VhYwY9VdnBfRk7O#q0qyEyCmJUlj{&ya4larczKu z4qD7;pTN}wV?Lol`~n%t`4?S&L;*?Tn`fQ_Sv=WZzX3@c(e3c6Xs3`nb}9f;!Lk;b976C6+oa0p3azt4!Hu_docY#?|{^3F-yEWEy^de0DFf7gLz$88zucR1VPLmHhVrd z%PavhJqMzKnD(*Zeu8mqAb{=dxCj2=#~OTLpvUW+e>Be4BQ`4ysYR|99{h&7N8dnD zU~yiSOHz|{E_!cPi{-9Ro&b;5CiQ|YsO|o4p1l@0QDUy-y<>5sf%7t0zYtj#0>*nI z-%Q*;-37%Gc?wq0QNEBoN&qlb$6LyVP7&&ic}V6ST7JEG;Xd4Wp($|iq8R{q{=SvR z^VW$9cBNN#NfK5`a-_4=?}11K08A+agSCa((83`4z{KRpjcYqU$FFa0EskL%8jjs8 zYnB?F;R@V;T_t29wyl_Q^5(n!5|GwPLR4Uj9MQm1nzVoj!@Mr)aV8=0(7-iHjP+~5 zfE*I5@}bP2(Kv+nM+aeE&DiO{2BP~Dhj>OD0OHCY1(>eocX9LGEzgjl!d6xKRv-g& zhS!bt%2em`UT&+d$FUGmvk-p&K1K8T9$g|xPyFhrIRt**?m|wOcdN>TWVAD117CtZ zmP6hqawNS|erBl?8-cD$x*HG6R%wA>IfA8IGK0>}VL%#QeE;^+qpU+bD%UK?0n0bj zZG2BvraBQp2#tKWo3iW!qdva?i@Ib5ej^t$Cd7=X0wFKicfUmfiPH_j=pOt7v$ zbDl9c^MPe%Sxtu^hBtuzWRZB!<)Gzns$x}bE)pKUZvZUq0(nx2v1L}r3|L;LP6D9* zI`_B3DO&Pg9@21Cn6*nz8o-BIQlp5e%C7_Puq0T<+4iv z?`}LI1TQ#&!~0?wT8a%1X_WT29T}dGdux12mmY4&$aWsogw0=4#NoW)s>-KFh{I7% zAXg?AZ?feIxMct&o#m@5HvmR)I}n#($j<(pGS8K=Az2;hrYf^p(qep1>ftUekT3s` z#;^lW$6!5FWm{#yuyVe>#A1w|TEpk>WIg!R*YJ4*YSN7W+HY#JG(3l!Wi6kd@aH~e zeAE&GR;QeEBNJGer6FZJUXFJ98C$Bbf2$>)K$DU;riDc;Pky#YUh@!}*dm0uaY#p# zTVf2!ddOyOV;*RmVBq>J#IilW{O)#J?SGgFH(6k_`C}_ z3GGjhKg6!;gWvDf50e%10bag=+?zVZ_TYCsifWhsGBBqA&8@l4AJ1D(*4?zc5Z$h5 zCzpj)Y?NlIaLdIJ5qRDPOg#PJe#^A#KpLFv9Sf*<>()`WM7n2dh#s6YDd4tdi1!l! z@^7a=gJ3VakLL7jB1f7Ufe;RyVnn^ncNy|$sBbJBg4iB6jO)r=al0TU-2KLGXYtS zUvA(<_53X-b|EW2b%cu^Wu#JCoh!a`;(6QErM?Yigi_!dlO`0Vmy_GM0EY%WP&{Ja z9RRg_|Hq}8@K`$Gr|XT7yMj4EJ~Ps!t#D2;j-3NfhlsZJrO2P$@gIej z9%r$<*)dt5*pZe)i>0mhUsDwLOhRaqXlLKRKv40ko(Yh`9HS>lGPNKnXYrpD#2FiG zVftBQ@&1PEqT}NH-5#paY4n#l&X^FvFgTQ-?xbOTpkiW(OAaON-y6{_&n$ia_njub zZ>l`FKaNA9&~FQG*Opo?8aIUO%8(+4X zH;q^z#5Fl8C?Py}NHJhcn#e9+Q>^#x!7V!%+?P_#$Ir6+j>wz{XMx@9_85O< zOS$`fdepjy1H{gJBj=TIY;2xPAnIVMo3TlDWx}}P`-$hV*be1AcFC_7%v~(F_rw^J z-)F~Iy*f$r0DiZM-AFE@VZl+KHiE>}Styy}*;Y6qxyjYQ!C)Afac;rM;HibAhG%Fj?Sm26~_YiHjwm;U=`)f>}e(n`)lEiUAYc|Pv9znYq*2DaO# zP*WNsq%vb5Wq2v=A7RH$FosI&JfW~@3o9iznX{v#t9PhaOog!m7^?W*pwDR2xfE)v zA}4%qBXe>?8dt0lP;>UOE43cE2HEYs8JMC6k0{QORx~`d%hLtlRZ4id`(ydkBcF~t=9?sjmo7oa zL`cJz)#u7t`2}TzHGN`;-@zXS7N0VSQ0%5`aqEW;;V5iIzr*;Je?sP`PZ690WD>4= zYd?}&sM=#nbx^&<9m++RB!u*^;Ws{4&2qGiPv`)7%IZ9Jc_3NeEqw<3C}3OCkuhz0o%)4gR2=;rzgSM$ z33Q3b+Y>Ge8{ioL=5FA?bPyg&}w2SO-- zp@4ddj$4Sgs_Hv@pn30kb4Tg-@AtN55$JRH6O8Z4ty4vRSypOf$0J9x8%GW`@=vT5 z+kQRH(P4N;A8pdr%iDxGoop`ts>O9ji2x_4iEtIEN>q|kqh=H=uW54AN)=4u@FA-z ztffi~6K~ArFKgXzWm6kE>vggBn5@;4Sh`zm zPdesX{!Cp|43q@sf3v{_JYf0)oFeR-((mr_%r(V>x&lw9;)n0r=nn2J>6vSkT7IBG zELr!}<{L}qg!_N--h4MH8xYc{AS|Xtm9^&F>{c(E0CnwENR@DHh%jV4zkEP`ve!X2N;f@MOe)lhctoN%-upqPFn@!Rf(Xg*5!r|B9uYbh%ZZ#S#KvqJYm z*jSJ}^=@UMFxDUu5;HHlb8)_ROLt@KBYlxz{`bXZr4;cpcRAC<=@9R7?ZN0OlL67i z$4`c8R>cy&Odpgz%l;rY?7Dpq4R%6D8m_Xt;_U>)%|(gQyKRTaJpW?JDPWE#S6`*j zH$@qB*~N+14juUNe9M#G(kC@d8l_>WcVk5eQ%$S_okY1;?Z}&iD|*ik<=7hzHH$B8 zI5nH6k8jY5r8rpdcm$<@TElXG2#%ShB`Q|(9j5!-q5e;By3Sv6h%vk>y}p*xHRqeA zTe%J7&gfDr1S9TCWO21$*06BT8P1sBSmWD1$!J2Yu?oV|Htm>e!Aal|3)ttz>MX>FFl-i5fs_G>{28yBLDq$ar4PI~BH?d@J0CHV zN?x+y_tp*J+~Ly5PAAIJxg|PpMq`0{1$`ZL+$M#nRgKo;-#P$~z4ZLdM_p&S?PXEt zBa4GJD&&v3MEm)o-=F2+xeWT#a|?xa@+Vfe5%2Fgx^^8dTuC7+W*V(h(F}u#aEmY- zMbFYb+L;>pE~@OK{ZXWtuf$Bwy8qBid9xH@nl1n2x1~)wGdGzTnXwO|xkS>Mb0PdX zQX&?)8}@f-7YNvgu*U$EVv0O%$?e0OPxm&OJr0mXZ~F zq0q+WWKJr|E6B7QJiwrriTdr^!&2&=Mba|M`-nbbsvLT#puhobI^nZJWkrXF6K4Sx zzuybZ&A#)dJ&*<&`N0GD+0iUb(Bf0koGp^2IG?4qh~FJLeUBFf`I$&S=Av`k^RZW^ z=LAhr^}Ta15D!ky;u!4fy{a#3PrUuDTKRHZD=glZ9aOlx1J#`p7WVoUpIy@+8QLpx z8ocd?*L9y`&=HoA%&q-Tu@|$wsbBRYZ?^kb6FE*y(O_ggkg^Xx2;lhf?Qpvt8G9La zR0#!{L*cu*fhZX&{2(}6Q+R*%{nh1UhTEQvT*GI}OCcgNRZB&KsRkL@ijR$nv@92> zBje7$U6Y`E%XKtjB3ij3IEc(ADxKqe&XWsf+0y%ik)0fGI~VqF(H_}@?CT$6XYAD_*^ysVi8^l2MU!60*0#>~H@pf~BA zNSof?_1{j|UanD+3qZc^ACI6xDJ{5=*ThkqOxVi+u+Zr5A2G)7ejE24@9sUy$;V|% zOL`oP>#Z|NKTjrzfx@-D}7IAptv>r}S4(QNyP zA$q_tVDO}t>8la@z=QP+qpmBv0|C9-O>Lc%a5Pn)zEf(C-`0~82cQJ#Q&UyXB(yUJ5MJ|P2DmZ zT^-L3w~|d*u@xuQc={b`BSw712$%4Gf-#kVwy~hg0Yd_e7iUZ zl0gt`eyk^{<>%`OF`bqgmmCZB zZp6x@IT0k=7EDSG)>!<~bb9Vt%N?GxD#lRm?HP9)%8f=M+1gsvBrTG?!- z`7PsGW)v#drMhElP0--0t%jYMSLN#sogidRAM?FR;5ak{@^zxfm)hj7seUv#=P z4Q5v!Ls2SOdLHG*O7;r5h3OV5`^Kn5lu&|C`E2o(nLlS2Q58aWdGcwjrQKOBUvDjnBIu8nU{4WdXw^Z?P(2p ztIOg)IsD0-fM)0kP++<5`(ahfQZn@w8RmR;?w#BftC!ZxroS)HiMDGtl><_c`fUv+ zII+O)T5m;u_j~@45x&g+I76Slw_8AG)9v;SJ%hcYy|}8FIkoIoi(=PvxfXSeJ6Qj` zf9UI5X%@6Jm>^y8U=v)YmD@vtNha6mwA3@NlM!g~QR`n4Oh7Sy;r4RsbLD%>oi>HO z4i1k>n@$}90Ag0Uv&3ph;b<-lXoQJXb$Pe-&fLl5=A{y1+ZM?Lp7gmEDA{kjN>=`f7>*a2C z<~2x4k(}kWI>)#m3m0x!aXT~Qw#?>w#>Iho90KmF~%7hnTUtPF)yc!lND8qG#?a zqh*#Lt7N^KCRxpAWb@;B_pMQz6TgLkD$iMSc~og*jbPd?Z1knqw`WLG79!|`SS%k& zBe=0OgchYCeq6d^Zh0ED1kLr0#i`|)*2l3yoU1zbch8S8R^_L;S3Zgf{RCR1H5y;{ ze5P+5g|4s?l~Vk5ofR{0lB>NF{X>{?)~}L#;QNyIXgAj^4S~D#1^JBG^lLytL8k}6 zmzx@rxLJhAwc-b4JGbhGjr+tzirN9xY~g^c;trr;m6zIVwC<+es{n)^EPv`&8|w&h zaJ|A9*0bWi#VF_<2zsf8J}_Re0rAlN`pPjs2ah_?;uz1v4QW? zR`A!9x}-6UU$@I1lW;c1%r9GKU|M8y|6X%H%Ln8n|_^6x{EC^*(g%cg&V_Ou<8)-xZo% zIWA5J1~|_bb+|7^9NaMBkJyZd-y}0Ls;)d0nI+%P*GLb&)}!4=dVl1(f4}oL_Pg}~ zq0bu`z`dKbDRt56@Jl^qtYhALQqu8{PH9#QqmUjpR>Y6J-{J7^1Rvh$jXUV+lf@r2 z9$_9bOAVZ@cds(-T!5Wt9Om5AZdTbVh8;K;DkFitzRo{t( zck7#fNycNmAMPJxn|q}RPzi}gCkKO9=PvcmlBCqX-HN5N=`W53!PCe4qYu**X8o?j zEza=Wcd$_Zt8>cD=3IEG1EWKcu4C-CToL0M38^YER>{A(lZZbTY(49f-_!)EphmyQ z(d)pN^vCuxrGz?<=U%o=luYaiXs?yuzK2#>N3C-fwWeR4%){Y@c$`uE$sX_$g-z{P z;AJd_JJmVnmq%)`j3)EToqO1m&cGucTTH{(<^}4@fU6q7PBOsy$kIgq;!VIarfZ=k?gkp04jt}hd2h2M=*y+R9$4HP_rX9L%WDwGc|{PFKpUUsAdvbwNzQB0MZ zZj*{c6r!K%TEshwPn%A2)fL=jcdNbXs~ffIWa$)Hr8}AWtudpUgeyqSy{1> zzdXh=%Xt+W+H5zS?K}%e@()+$Lfs;MwCh#k9eaPPKS!Zt-X`F7p`!I}kCj<#*Yu9v zU~ynW;CSI%?K30$a%2V|Fi7NKOM#2|BZUi2bXGfkUJY3d{8nb>L!{i9Uw6?Vt znl&asw?zPvq##hju%`Bt?rpYDnqTDB^NPPechl?C<7$NC**GML-6!%?8XE`RY>=tA zP$Fx|)1(PlV z^7_GJqLgV#Fv|=%<;2VWIsR!~bcZ}wy_X*;$aQnYcGqg$v#M`0x|nw@J8aKP((8n*+#M|Sx8wOony)x(HxjZeZEvv;cSmI!-)j+ka(HB zjl@@nhTl|^SbXw}4Xw?oIGT3Yz%$?g2}nYi&HNEpok+FGo36lox94 zc0!ZH+0=0_^QFfjg5`_?AWVoND(Gy`4>w*01uIiDDyb;*MiN5tGt&^`kReQ?R~Qj1 zC{jUHx>^eSF_3YfC9~ip>!%m*uFC-X$t~*zXUu?e@D?c-v11_k-(eoGO!{{B#d&{D ztg?Rznmp51zUTg6m$3|QQ?5dFtzLT~U*iuh52%&&x!oJe;v-^g_d|EG)ETTSEeu-J zkSzLj7U~}i6S;V<^zOS)g#?zvUelH}Ix6ZIs4yINYR_X@Rw`-c;b-8H6=!ONK4tVIBpFvMOJ{wjo(kOTI`H%jid0;5${E)E+8)ryV zq-QvbQ(^n>-%A0Z&7y8tcMlt9UR)_we{dG}srCqmurntb?2TE2o%FW_D-kiZYJl<$ ze4(@8a(nWPhcx!H`H=y&uQ+-~RViD9UUKT8#2JmK4&X;=4M%NnG8tEgzf} zKP3^k@ZUD7Z{@*u8G>r5rA<=NibS%Wm0XMYF#rAXvWS%C5N}a!JL}cPjeGg0aox>j z>U48r!{2=O=oj=`>jL(ZF7CzL?!gL9;nFQe{xh{59P;H#=qAoLv5b-38Xubzm?6?k zrXIHeOHT0L)&AL%;b^e|XM`csLrx;0JaSkHQiG*lEY#Gmz>`}3Z`Ax^Fd(`JY{LO; zrs%F$z1PH5U{_^9;(PnT3z862g$U|y5AT?FheY*bK11PL#%j!9k z!|fd57YxWVm&JPA);n$hOBQjqc0_wUBVS>GNSn;y@!iyKwpA&N$pG~XWmn`ZAn~;d z(DJ)dnXU+Xw(&Z`pvLBQ-H}cRO_Bk~zf0%W+sWak)lBzQ0sAiFfOU^L-(S||fLDp* z2^fFi?XKjV!@YN8>Mu0(qaUxXhJ~TZKFd*`$YKXCEps3IPN30bs9bS_U7qkam4&+1 zp4eGT2y)+T58~x1cgdD?9d4|j=LU{QUf_s?WGO6Ca1imqg-nn`O^l6G`kE+YcpaMA z2c1U1uHXPZj^^*F_aZqY_T^Fk9!UVy173X}=xXyHeXDtxPEVBeh)gz?2Lg^h3f$$M+Nd19#84CSpT(6SltRD|e;Lf3nC*2WeTZXljdX}C z&~rYAg73eJ*RbG?UXmmnV*OJX3{J38PbExGf4q(Y_U_Yphv?+QFXG5M+)|RQ zbtMwlT8#e<+{qzF0H5ME?>YHJD_7A6&}&s(tFUrHy2N^^L+Du4PvhLr=xuvmj-yWE#BfaUx2hS4?Uv1 zIt(S5I1Fp8@u@g~yWHmkUYCOylaGj0Q?$ANw&a`-HvU?}^SajERvzC$59mN^xZEnG zv4XYvZe3@9WRAUlF7FM7kMu?J1*wfK5Jz6Td|6$l!k=?4%c1k`SuXy&-(`R!-vn3j z?x2nX;~T2)V~zgXj$gW4W;0oEuSj0~XYTWXxvwuH$_hE&!jtmbWJ**t@yF0bVdKIW z8vWJG-Bi8*6LS*Ms2bp>8~oT)!^{?2EASZz?Gv{pq>XAs023Rot-0ROs$ zdxwn*I@L>z40Y?)2dmfue)%0Z0Ee|DUW}0kCTmX_sfd+QpyrO1D-fm)3$w`LF1t2M zG5TQ!d|(!ir~5<1uZGVt)OW6jCKvV`N@e)>*y`zII%I~1XSuiK33o!(tDCaKVgF_` zYlP6Cf2yJIfZT2%C;+uD_9DHKN@Go+K;^4y<9o82`VDBOf4tj%GpU!PKGX+GZZ*tl z4zV`zbA9&vL1#>p3A*3PMw2pC5&KVd^Tt}M?310P6<&WOUwR*q?&R^$rL`-=UbX>3U#kUy(rM<0%xCWcJ3JeQdln`aJVV*z zTI90ID{J#Zz+sHEu5O>zt!`2ox(7BRh_V6#q=|Eip{?752$yQMP(W}ToXIRYXbPyZ z*_8+1vQIj%iv+I)`TqVAxuup9SFn;bE=;XG$`SyQ%x>PS=;j1z+Vf$9!Ttm)Vx$@a zV@e)9F7N5X`+K3EMOCsG5Z+tmYz-asD}}n&IO22=rdV&V&AoF;?2aQ5y*qEyC59Li zGSxPu&%SAQ@y>#Fs7}%Qn`eu*vNEsM7%>J={W3LO9L_!!0hE$)C(94gAJ0gBXzzSs6*K8-Zjrv!+PAMX^KH)EPe*cAh&sMqF!lWI3SX452A zF;+Xw#b>q=Ny&xIg>^6VFW}mm`#OKJ$Dtc*wr#`E!{3BRd46*!=i_YXM|h zH_+DiNrelJ?bho0yBe8D@~YJ@sAKkgUbv~DDI_RprwodeS30_qJ2>|{LMiI?j3lpv z?FOFe6jZKGF~0k<)2tZC$JPwQmKB`RB`tq0*A?ReD8whwG;|ssp`bJgqnun{e>1j+ z#jV$l05+%S|C2=mfo-ART_~i&9?x}H-Qourhz339pS`0NgFkunZ0dJa=}SQ#5AFsZd=_f7Ns`>tHo5 zTW5m$)+bA2kVFO2Ees71U*{JigiV9VIB&Q#47-pMr+S6jCvj;07O4D(AY9*4w=Vybz_E)oigXZ663FeZzekw|VBv?sF>B-yQKRqn0YR!42Hp2K4gX0+F5! zW~ji2UjFwOl=Jv)ktY#&d9wZ+s8hHtH{S#jHMP)LMOBT&9?ehm z%|7!6WZV6AMkgK7^ne1^JZK0R!0MYR>1Qb|B*1Mm^^xA>67;Rn=|e$D#D z$XjPeXA6+I`@x%w=@Xn(=B>krmt(Bgg%ZsYyx!t=xdCkhzb5fc!{`j}!x@C@#_XgI z(I)}L9-FxC^hJXfZhRHG!FYY}A{tjq_FUr^8(}AH!=U({<$jaRtHDqY73YUtSpK*! z%6lDYx;7m~opr}n0>`xcg13%#>O&U%KB!QY)pj-U+*Y~fMD7Bzp+_l1P}GiIp-sub zTCs)%OqVI)(`VV`h_^sBkGK0@roC{D&I^f3m8&HA=A-#QEF#MhI{T{vFx*^!Vm`MR zvv-C{H4$Ty?>;bE_nYN=8C+?*{q9!ucSS0u@O*u&=D!<8%h%H^(ZBtbR@OTP5|Kw(AU2y{`BR)ut)9F1A_gX!F_N& z4Baadi%ow`;ij1Krl^x8uogHvGRH>897s z(f=Z6X+{HUnxZ&rKn=x$k(UlndupCf`>G^k{?^l^5y;X#?C;lS89pxn)6v-V*iTe1 z_;~4L0EHGdLy83Gjj%RQ!6rXcs4H-0zZN@ll`b4Z}C1M^J4&qA@HG-xt92pN@Czw7v36W_&g%A;_4xhh8y?z zXX7J|ck1hR(eNh70;SeBRf0r$LK9g0{4J~N>;mI2(r_l|O8FP zgk4JoOaQ6CEz$);L&HNM!18_@uM8;511anNx!%D7K(+9C*ucw(eU2RQvbz2s?`>Wz zTFhtjlSsMvyvwbmC}6u?KmFd;Dv#qj-T7s=D*Im#s-p(#Et5uO^_uT2N`WR56JkD< z3ynU3m=O9Im3ywh1EYY?9e&)6Ao!|_3A{bNTNr^klU5CoxLtJ9kClRKdN}_0a(r@k zm5VIN5&Sx!;Kff}1Y=>Uh$Wzp|NJ%{5!Q72M<9+p zyxMV+7ia^Y%&(;yaE`Cwa%ly8n`M?j@1dVM1#~V=Cw71tA&GSHi>6l{|C5KB3Y=3Gb-<9(pHUGhE zbZO(E(O#9H(&3~bB>Tr@AOE6b1MJA^&*;s?uz`Nja0+=Ed+uE{ML^Fq~ zJ}N-Rbfd*5OR3%5CMdq2mRJDa=>|Nnu3KNR#Xjfk*v}G(IID#QAZM0d&w>q{jY0Xb z>&<6kQh>!1aCLuGPZj=C_Ue)GO~6L3vZuE_RDzE8Ilgpx(6|ZKIN$r}37>EgJhr>X zS(jb44BTzU^G(#{;Nz`&QX zAHrMxo-<0pm532@m-1auv=scQvL;|A#<3sD3qGrk?K>5Es077>NA?89!X;?o8U7W5R@f9p+c2V;mS;wV6*lGr- z@&o;;sAtiYtM8*UzH>??@+b9uLUoL-Qj$TNB_oF zW?>*_8&$h`N7T|?SFKH(`U7N^0%*5u=%yHdDch;SIWgykx9sv-Krmz>BVNJoMs92v zJkJ6We>V+3Ty%V>=k`sV^=7y9Db#;Sn}#KwbNk9RGrOfPgrbKZ*>l((F_*mzAb z=$nM7arzPia-V$P=F<{;4Vf#T^~H5i+p9Sh82kG^*_XM1ZQXi*eYB!XN8JOO7S#}@ zzS}-_VLuGLQ7ZFIh84UW+P{OOJQ!uPp2=l-d}z7#lBh3thP6afjwIgLY*1Hmm;hCGg%hv(0ihFRkeH6 z!BrvHba#itL&y*4Z*mARjeK$;#|`bhnbt7g7b^Zqj%0fV@g(zb-WBhR_~Q7NQ_!qo z^qA)U@Zz7;-A?{z_(UTku<)B(Bp6z0pIz?1fBz29`+Kt&D7r2N2dc-kP4}E%bkCjv z%qz50igw2}FN)u!)D!=ws_ghutNeBj~9txjDLa9(g`dL7h1FDt;n52;IbspB!-TR zZvIMyAIoZ-_Z*b@)fnMo$3ZGAVpL@pkI9U%&?9k^=}}=awGr-j=YX+uYd15*hk#R^ zYJWCA{dqagY}K$Hso*If`;qj8j&r{u(P7dxLcIE=%s^;lsnOho9PrTA(rea!0hoA^7;O& z#chC;K6%3GJ@NpgcC?qMs@{t95`tghy^4>xv~wnJRXiBRtTf_Aj)i8Jd^ z;mG3`FqHAS$80t-?}#RMo^zprbUWj1cpz0)lov*`H3L`sM)upgqO3@$=kiz;h<;>c zSeiBjnmSPkRcR#!T*+}g?5q2gy|_Wj>5I0O<{heC$o0Ze31@8!u^#%Am~na$KXtsy z>VO-?rVBgQLduk-I1}a#@yNs`+6*F#*?@R6}>biFNFT* zG^lo(J_VVv1r?3=m46q^WRZGg%dD)MO-F$3z2{o0j1)L56_}yLx-PoTPy1m@L$=7M z{ebz_)zlHYv$*f}K--D4#(nxx?OhJ_gR&Axek7^%+>`*&&3)}ewg}{i+EW;Cuvhbd z$RF%s{iH%%Sm#8m&@4@&_B;KbeqgaC=sdhwxofL;Tt)@2{;p4QHH&Nq$6B$%kN#~j zlsBHI+Z|#HYd3P5%ED#>*^dO9-RvsgL z|6VW;@c};9J3ss3?MJF1Pj_65tm-acQm?fa-E-%#1r_HzXHgcI9G}50N}|8*4N1e+ zW`mN(K#=1D%%F-Nzuw_K*FlZr*`wVxm(NFi4moQqN}u8bJMGvl{xfmx+;gA28! zH-JLIsw?x%ZNL_zC(K4Xik?Sizr*KS`|9V7f@jVdHjN$fp#UastMkN3xlPE~gzVuL zU@*qo7ioa`W8?)62dacjpo`v;thEx2@0A1rGu3s9s!LE4{23JG*BrKLGmb_R+va(7m*>0d-mIvK@eT zXIY3CWolRXWgFcQn_)Y90g3YniALr{%c+Q;n%RiqDVc{p7+LlpD?vgUN!pf2np<#& zBpG7e$h_P!>Ss%GFL`@t_gRC$p|;)Q5me51zG?k4+oHLt)Eu^w?1Fq^XXQa1&63xon^NW9oIzV1V1MV~hdoxIWP3Weh$8rGE8JbDHdA?b13&A( zhpX>g^`(x~7@)AQVcyP`y1k}bz~@QLKwya7LFcuj;jw}vz^w8Mz!xt=*WvC#M5V6L zS!UW|@D}AW|Gf75ua4niUF!GJ^mYK9Z2I-vDWVoV>Nf#JqKk$GtEV;l9nJa;g#_6? zdL)V9c%h2pV!fG!GTC>)cL*k{yCU1au?u^Dw$@1yz|z@)>&j1z6=Pj0G}$Sqoie9n zveJj`Uf}rTU1&U{UQ@6zsBMHP|Ik^fO)}0>8R72nW6|>daHIl3)1&=T0e21|eD@uI zx}T67r0FREqM9+3Kd}M>;ymAPHUxZmrrO2?oR_r28>*uECNs` zt&{ox(;x@L%O|AAppEvs#*CF!S|_Gg7hs^%0<9O>*b)GXLV?^H=NomeczIlY{D*jL zlJod4;_>`qTf#C4yzR4sQHW!>fT}8{`3|{=h6ZoU&6~oHDJ5^-e24g<+S;stMFu#F z1)c#}cyZ~As;U^Rv$OM9BV4ijPGL0Q*L~&6L!vx;MO<^gTKY49GR+O^8OIr@(bsn? zC7uJ!Do&m=PdkU=XWTD2!gv$c0|fIDfc6?Ko{Ow?+H?2z+?ak!*OMHIG-&-|-9B>q zw_diIZ{?@y_olg@N3^wF;qL7un?Kuo;6@x?+yf1`^t3jNX^k%h{ru z_Z4Nni)#^QDTwN4!3IWpUd8LeJN?v1a}>=Hw4Ranf@%o7YR>9P$=dA0e2E_cqa1FF ze)BTSF+u=FI>s<_W3>QYSxFboBWM#pr9mu49n_|D$8pFhea)|dx5fo4OD{z<%(Y;O2ydt9+=i_hkZ68*vPP9 z{6MqACewpkam2#QEj%JyX60gb#;B>PYj@TB=xCtznW-oWFubSj6;D86kfE6O`gfLV zqG(HhIIATlR%d3=dmfak8&v78H{dpfOhTxQf>bB{&*Cm(SBwsn_7r88%B&O^;kJGs zw!t(hh_#mZwy+SzITBYKxaGS4Y_aZ`i~F_g@M-2qcDGM3tH{0kI{!rr*U+^gTT-FXlIcc=9tS+QgPSBH+lqXAwwt`Tj7 z%7t+l-?&aLDzY^dC)9O3qHT-fiC zY^GVhfT(%di>ueT_>^5F%@XPkn+b<^8$Hf`Tk*Lu`Dl-P<+I#DwLb^Zd^KVQUZtBv zl82OfolO=&hBm7;;1}>5&uTs2-MHx}zx*dc8y}7x>0h0KE+=HvH z#qUKzs~_be27exm=YevxW4Amo;ij|o@V9MWVqNTq#vr@*2d`h+Nm?%=2Aq?;5XvYR zneauuH0fDM>F$Fzsi5i#roNU%$c2C2k>{GsISj@`e`NtNmT`x-x)@|Fgx`!2e%xlK@4K#@&JnXH z5RA3umM15QzPoqEmz7v@M3G^rp!?x!N}^_VpK>{)%Z`)a<9;tA9!=Jk0~NZKPh(U& zb?U4h9jX}rGjrXRU#Hr^8>_&TaM<3-c>=<_rx`0x%i2mY(08oAO4%O@j4Unyu0jKbLG$ z3dv92P9!wBpd7(6>9uZQGD2Bhi~Q>HEF7NrTTS+0@8ubaY3Qid_XSNUINlZ~iH^_Y z78_Ah6v8aAx}0saRAVg<>bdSHOU5@4{Smakdl=}8}cb>`Nir#&msJhJXG2*C1!Pc4j zD3s?OR(Pk_CZPsrx(*h-#`38#QQ)XQtTIIob z9c?dV^Aa4E*Y+l;l>&Wbe3 zAOjt_jx>_P!;3@z8Uyrhi*{G!x-IAp5pGv%)?@oqtLBJU1N4l0Y;-gdlti7QgM!17dHVLurx-REIFL?l#)De zAqwK;&!oP)q9!@o6WNDR3ey<}L26t-!ZfWbf-I6vJFi2bthe6tHxN~5oBF)&HRQWl z;JllIWW6=>MMST#U$<+QiN?$%OfOtg#{cMSmgD=V_6oMtgDraGexNBtJ#PIy_gk5~ z(?-@qYOHzXQ+XS&nQ}r+cnzcXy<}yxE4~U@NX@!dLt&2oRp&bkFBXsZ?d56v^5E|z(IX_XS<1_^4c2S=Bgx%fBJu;am z6&`YHe7?s`oFW+v{HPGHTq!alB0`Cq6ewFm=+*P$5cKF*i&$H={Lz01g0xr(nwv_* zyaJp!Tl0NHp7msLp+L3t>54^^>%X!RlcNPg-8vT30e7OZOBH6Lu;qzh1NSLb<04*$ zCBc!_aOzvtP@j3u>s}E0%PL{UNzM9OMR;UJO3ai_AVfuj!PxX?OvM9Cp8a9NE;?XQ z0Ny1x&#}|aKQpzc`e5|Tuq&-69~d1!f=R59W?8O3FMK{e@>8O&mznET$=IMnG4dg+#VU>g9Q8o81x>XLEgnBb|B_Z!cR}|e|EL3AI zB^GsSyCq30=F6X8rthLo`P)D246JHct%;X)ZMB`vRo{UoW>pcRD+x%3oZw~G;X)5_2JX#~mGqQ8k)InH^XoGXwjby|QlmsrR1XYW;=|!Hnwqma;aXCXYr23{aG03F!}j!T-{(j&vxPS z_D8^l7zlewA=O9)fz-nM-(bH0I3*}~%9CKjF!Z`TAk8Yxz)*rt*zS(NA1;G*XhWlO z9o`u(q}!jxwxY+^0ew%Jbqs!$WjE9$vzyvSf zu*!P64QcS^cw*{rm|^?x(Q|19wTq=3xVb@I`X-EW2o)Ci@P*RqT-Brn40ANt9!z81X~`VWVt zw|}Y(Z@4#l^Thr1H0V9gPG_$9zDpPT4cLHmCjv@M;olSuI6l0*Hv|kv0hU51F_&|& lj9(x9=QEQQ@Q1z}Q~V;-Us`8s6CnfQrmo42GVS}%{{?PhB^m$# literal 0 HcmV?d00001 diff --git a/ros-realsense-nav/turtlebot/doc/img/mapping_screen.png b/ros-realsense-nav/turtlebot/doc/img/mapping_screen.png new file mode 100644 index 0000000000000000000000000000000000000000..1ef34ba4f2d03e9f693fd369c9668bbcc000ea6b GIT binary patch literal 260595 zcmY&)`Tn?|Z-d z?)O)%?zOtBR@ISx&fXQOq9lufN{k8s0LD8xDK!8<)B*r_01Wr?M$Dir;bnk#k$9&8 z27{N@mDgS#iCm?1T-6;cT-`r7n*)~i4tD0OE~d`r=JqaD4z4Hg9U=fg3A~dM*YHR` z%y9R?@15$jtP*acRrUh65$v^kayxZ9(CAnd_|IJENO`nI6hd!=Sjx-mBakFVh-a=J zVcL6T=|a9(rXRWf4lT}#Cc5lyE|X{VK8O;cIvt+43^MI~$7-0=#sYs(1^#!@FT+`M zp9OPZN>bA4>FHY{Uxf~xpGW=1e#`AN)IwXcdJjb$_rFTc&O*!DjmWS+wy!q-VGDvt z6jPq=k5%Z;!gq$K=FMagGJ~B+`x7YFkChN&Li;j(X7U`lbJ1&DneAy6Ra8)jrC-rJ zDGfeopDK%t_}AF~Gku?Lu-fb4uv|vez96Wz3sn%`D}+n}1aVx%pz*fpqD$mp9o9A@ z4dp>lL1AZgfJn2wt;ez=lSE|!oC&*CkyeU818fwEEp?F7E{`*%$f?S=<& zMM}o49+|reZ=;{rO%&DCj)caRBox^id3#c~C$i%$ECeEDe7(Mrn9{u!stcNG4QB(0 zY~C(^vsWh&A$R_?eea@-Si+JxVsL3{C{rp-yJ!I}Y(`|2c{mzo5ss%0#=IvZddijn z(MICpP&*OBBdQc9r+i;`@x~3Ktsu0Vf{0`GCM6|IW)=Rb8dQ8Y{+GLYUCZE39iD@g zduA8S1hzqw|D851Wo|zL_uVHZCbo_U1iMHbQ=mqOom|(Z1HTG*O<_M8BY84H_aBRT zGBiFJj}{&itgK5x>!+HeK~fwm?gQ(kT%liUXxp zbC-L|XjGT|S%Q)Z!p`J4`u6AfPK|H$L4exSBtF~SutqLRcHoX~jXygn@Zz#Z>sudrVeo7^-|7~9t{0>9 z-Ya6YqUAEfC7u#1EU^Y-q07gx8HP!+F#124p(LWBmtT=>f)r{Ve;>~nmn(yR!b@1m zsBY`Lu4OLcDk_0Q3c~~{{#+09SM)sA-i-*8;8CkCkL)(8K&B3hVcDU=T4NipPdM%eFmUqSjjj4Dog0UytI>P0C2R4d_rK2x z0Zv@3SglunLKQ1y(=#*9oF4*4dJqBD5GOuzEZ9;7nMild#W@(f|A`u6&8?erl35t}mK8h|RD8mnuFnvt&kICa_(ve#lTjROrK` zMsz=Hq*32!Z>i|RuWy!0Su6!+Dc~q{hEOZ+hvC7(s^AgfcqU@jx|?%b-*J0|1j?Ap z845~3=dg1%+B4n}oScF?5?oCH3g8%E!Wl*%hXt=Pv_NK`wG_w%P)2G+RLe=dT~fFI z84zZ~AoEq1gR+I@ud~H@tW4Qbqe)3aB;9&ro=BG&7_zeGdM}(wNe{?D_`@@K(^!8p zR%?udhN7O3w-4P!*%4pMe7iBYH5-Z_cJzX?cZaC=pz*|+@DOoO!o>;;R}9oLVoMaD z%gS^fB+YDkiW|3#ZSgK80{|FGs8`UdkXKi``fyl0r(bju#JiXbKm!Q%YJbI`eAE4f zPZ1Z+VjSCr_}Hpr#@xzi4fQZLaGq=GQSt7EwJuT{O%j!gJbN+Ruk@IqO0=HkvH~$m+AgO+tW~1K70Xqff1?KLVvC^R1LFoF(l9a>BE}Dw! z3G8PsxeXBta4adB(H~paD7DPBZTbXrvHd4uM7&*x-O_Z^Fl&}(PlT`~3G&m?33IbD z4%Y;HfunqVD%9_kOZzSOtF*LCLUec}I%bE@_E6+BiI?F5(#*GL!u7Ko1N*8w7qMsU zr8;ZX?y~|X5IXU^Lw{7pTonVhM4iCVU1S=?{&>6W_3lcRKt;UX*Wln~IVIgU?hU=p zE-szxj*6LYxpys{<>jTMdQx1H>~dz`q}9i>!gWU0MRZlcs?=NX0Y_5mAd!dhKmvBd z(H}*uh7BJldz{8ZreI~}3ej17Sm;P;ymrp}TdM^r0aQ2>M{~ShcVCT^XX`-*xd0G9 zX~MA$${kj0AF?Tc*hoK{aikN z7gyxp?pR3)X5v+IDOHnq$S;%$3T6&_d;3UaQCk`G7dyxCV~A@@?G*G{U^XnW#tH(p z?P#?e4ug4Pa~F=gGL+o?5e!_?tlQ%Uo+CN$dHm`>C_880{*|tp+iLX|@o_o3%{DD@f}(Uhu%2}kw#+>3Rp;KQgi)r0m<^I0s;~90G^iFHeE0in zkG;^YlVutHg756cF%a{^>+jE1^LCla-{^ERUrR;rK31{4f345A;OBJhZZr3Q=XeaQ6-}5?QLgYQPNv0tEuB7Ub3at9|Pwp9ZS-2U-1{@C%X*g^P=$N zkDDc#(S_$ms?tt~3;jf|!pD)*8s73C0?=LLE5y^Zr}@^?2yw}Gq1Ub}`iFPT91afh zJCbE0PqW^_Wf$B6^*@g1Q+=%aKlr!pERORWnfmEu2Fh?ZU2Gnlm;z{LZ61X+C+w3q!=Tz_{_WKzfVj| zjHGh&yIi@VXjgk<{lMVzPS*Qu-i!+_^u)?)4E*cHtKD|}*9kKiu9)UTQ{a-w zuvcg=@FWgTuOhkDQLUn6jY-|;dnBtMPcbzBB~_7PP1@^Q35q;mA z!~jDaz#QQKbZUxo)Q&><$#Kb^UDS9EoLNgk;4ts|l-gDPD`s_wT}oUOM;1QnlB*HD z6MhVy(x|ECh~53-s&72;sC%|@6b!*$YJN`$z+~_a@!+!S8vMLFw_SfAkUg)$OBr(v)VKmuC22 zyiVVVrTnMf^KFWwKTJhEyBDmt=feuxm5WnHGiBOGFp0)6yw^LzPlay@{MyY>x0OnpT zd`WX~1^LO&@=O~ZQIa8Q5IzUFVniw_@dG!cZkB-9^erT8YpD|HSyn^$3_*WHz{t0W z9Vjq>DA^^8Ka;+_ckY^t2J6 z@rKB68MhXzdlu^~^*N!IW3r|@q^G^GWPvi9*%e55;g9*nM2s^(H~*o+cc#2X47mfr zx-{Q8wWWLK^XGo$0PTTUky(#LH2V|lwMM1**FCifjU$5jxZe0kp|NnD;URN0UOlaON?BoD3H%kt4pszdc9d+vLHPpukyZJ{cep0TQLk{fP>{m8wbsaoGBaHCM(9$lD@9m2u=CYe);ln zNwU(rT_!`=roI#1ovs;e^p zp=i%!sz&=<9DR@;V&W&GEW#189JLVJh6Ij?ahM5MwPn&EeJ)Au?~X&q4z7HDJU}c~ z<1RPP`;n!lr!5Q2eLi}pdCu2b4AEpp0v?L|_>X7yFH%FMGf|{NrPs!82eoU$L{u53 zd^kwdY?sf0HPLFf4w`QK#2WAZuSumdkm0#VG2}`-Z~WqM{$2L9*THf|syGN+82dic zv)<=vh9AX5TFxHn`r*}9++K$rw7_j^xElg=2y?#WOsvvtb6E9jT%s99&52hVx*#1pTmR6&Q=u<%ajAaN zdV80okVGNug+64(U)KNp!)+xbwt0xY@So1rURxx zlLgtpM8H6T2SRf5XZ9wird(#T*y}%<3x>ntq2v@yH}HLlSL;}nWvWkpAFsyEoXPku zUd^8p0Q4#}ylxRUaGhli(UQW`=kT#mfd%meiEqCMX6-xg*`*Kf&GtvpS@tokD>lp$ zQ99Te-w6RyGC|t|m%GX!o%A(o1K`%5hO`F&LKxyvVP35Z1*Jha4OI(%0xHKP?HNNf z08oJ|bUCc6Rxjh)@(R;ZYZKUTCp`@p+KOtR0o?3SzdX1jQE3z#*UhKH^CKXD=!5WU zDqWuA9I&OoERZ!>g2Yg$>QqoiT0b(WAgpP-iV(vVlu=wJ$nTF7THN|&IY&Am5@4F68<%GBiT@m%xizVE;N19&=h2bCUW0FnJgTK&Z zjjet^Op3tAxS@13AL$RKVQD5Y_W%5jGIv(2_O5)OEaM<_V8PdSd4Ap7COTuLmfoRQ zoi}|oF1HdQ=K3&tGIm9(Avu@tvc#F60_t?Px&TFwX1na1lu^5xvH}0o$U^V)kE`7s ztu*X7OEPvx2&|dgwOJ`&fXAFh!9dB0FD$Z5=ks)a{_;!ox#n@quqDgma6%!8ZFMn; zv!G6OQ)VQU2MJJxxS-BNLdsIq_OCpKx8NL`eP7D{7npZ_`@o=_nf~VU7BZ)3yU(rK zf*Rh+iWHzr^{VJ1u>xf#dxsB;YRkEau^?6k9`MUbQY)R110Z08VQNuhF$r?X(x1*S zh9OtvUrU(jS86wz%7vA}d(%WCo=Eo!rTTEoMt?B?oc`z%!!iqlTj#l0?2DZTnxJ@g zV-TQ}DImP}_z8dzVHxG8zhyy{L$M5ti~%UuuVJDODQq+Le`?h|Splf-mKx@>E2B!@ zC)XnT31I8++IzBIEripZkRqOBS3TP(qG2U(#Lnd!v0H+h7f&J32oq^dlDXfC=g>Vs zEU&_o#!ThSo)jEcac;%Ehx+hg#wXS2b~QX8zKlWL35AFp_1gIhoIGPrz*tEg5l6Nm z<4rU>#pBt@AYqPcmWdXKwd0V;KOZ zd-5Qz3Pq24YVTH54nU8M2$L54I^5$%~j(>?B!lte4 ziZ85<0qEswqfw3yyw8{R*J`|J3GWg96EO$|2L^7=`mdo-fS5#!qIf-4eBjhe*!<0xiwI8jRFWfupF(1;nGt42Tjlh5>a*bq0+GH< zJDur+!_k5;uMFeFdbsY+B+83Isi0s`=Zf#W&0Oh1(KXshByrVusSGVNG2bUKN+?5w zHx_Vp{HP#YGtUT(Eh67q4u*`jIxb*L^vSc2q|WdRmX*aEVQ%nKz>F7arWWe*hyWjC zKcStRfOiAhf^H|@XrkLDR90=rk(rSbWLV&C7oWoGKDbq%EoHG>ypBB?tNt|$!TqkD zK5y2Quu30NE8! zhxZqmTG#m}>4HupmE89f-i^9)Nhnz&xea^5Kd&0OHkR}?JS`OG)(!Q804cg-lIKWa zW9A?=^4nscxJpi*7icPg4BR1m`SU$X1C%BHqnXuT|GI$~j}vl|Sp_)%I{OVT?8=?5 zq9LIaJvKYr>{dqy>k3|fdj54|EENhlRlnUY%u?4A#X$jpq>kl8tJ!y%0WO+hvvv=y zWW83s|1lW$Kt83SIaMes-fNwTSe1RE;ll$1<0O|V z1K3P-L6h+$Oy1W=>i&zi4S$P^TXRu~_;?+*&l7Iy4|ogmX>sK1^p2*9YVk*(ZFKmBKi{RBQA_dafv?-HGev-!o0^L?$xO)Rz~B3G zg=o>c5Is3Yy7;U8g^|rOauMfg3h+xJ$ytS+damyuo;o|2u0Uh@8XVwvHJW~)r`SzrJU4j_h$LXyCeBV~% zs{7U6a;<^wVfmhVhfedxOVNuZfk7g4s@IY9tJ^j#_u*;RK2W^>qL&@jBQ6y1^m8O- zBxp~m4)fm*rBC?ydIo?(FBZ4sLP4d#})w2HOHTGWdfi))!{LdFLywGc}yUq zrL()8sLaqaUb(c)vFW-es0FGr8u-cYOsq?43w}md=5w6PbRhP<+U_H6%jv1yjNrif zIGaev90qMX4T6WmO}I@^T{FWn84~32e{?V6-G7Hi@!XN>Z{NI;6DwZDYw*0?f}?y@ z#td~|-RU6Jd29WtYw)%7K_5NbKZMBB=HYVV^RBTw;iXrW=-OE+Rr{wUzlTqoysN1Z zG8GNBx6i1MEJs$6^+n7jKTUs;OOtzTV?Pd&^;8yS0Ll@i{8P&#qRnj9VLpFCE|*bF z-jGdsjC?FOIC#YPNAczA)u+9y(~uA<$>4-SR0+AFVQyF+b?)TkWOuiOLP-U;_g)wG z!ECV3NQGVl^pFvn<@dzR!NCMM4c3u7n69k%9uv_`#QQp3rhor?;UXTw=!5}l-6E<& z9x#1}$Hov}`jH7(r{3?UGCJh>U>%hoaUvW2=R3KEl--Nf1a@Up+^)0)P?{)y{FvJp zNuKG>-X{eKx@L&XxZblA$*SU`D!!m0LroGmWJ_^&ve?3je1)0#XfM8HOAjv-FwDRV z!qloIrKSb@#0C&TR+7Hw0%5hNB1UKcDxuJo*}uMHi{nKRc-Q3gt3ZXeSA^q( zbJlBvyN1EMStEROs;G}WNFiJ9mP2om#9BM0b-BpjSPn~xs49!QdOn7&Dlk$;aqf3! z&oD#JxiU^z%6Hz#S`f2MkF3kIEpLxvp#kK*5Jy^q5Q1@=PAjfKjY|(iVa zbyyp-bA)MJ)^q7lv~lcnDpx58uSWGrgLg)a0l=tA8RGFSR;G=&)u3sfW0QW7^AKa7 zmr&@(YHU>^g^Eh4tf5@0-@ z$Z}CA7i)3a`Q+7h{8++yFjqC#ZfE0W9@L?n{%|q2EF1kSY=7xZUUgk7tq{;9<|Hvr zL$;JuFrgn5u=V+ZjDCz%CGYFAMvk2bVXB}r}Hu^Fmn<98xCSE)?b!$8XC z0XDsxDE}1D*>S%@Sa~@GJb9|f!;9-eJYMCPs9Yh#*>o5o0n6T36V_a@v}&j|xmL7T zcocgo-&~=M1ALid>8zkg%V^uxo|4i2oUop&r1DOyDR+Pm9JI?``^DxNzS(on_i9f#N~ z)DLebj&Ou8X#BhzN-#!)tD3Pk_APL?vKnA;Apq#=);64;-_ojP<3c2eBl9brfQ2GV zARhZ2Zgx+m6sG9(6*=S3KZf>(Fhbv=ukN~HR-fYsC+883j56cn84*!REG-fGv*6i8 z-ikNFy7lBs*<{1jm=Lf|A*Yv0227Kp79a>;nxwT9V*VGcd<3$rHHjMR;} znz0$5!Csn9D|8i4cxDy?o?nh!m@-=~m^8JZX z$B0(mXricp+p6Aww(DP1u(B+qN#8*Ki6S86SXu4;|5=8~n#$ExPP<& zYj8$^-E{ol_=YYxPgYw)3c_D_srQIIn&k#5yNE_>SO74jivgmNVv^Q9hCcr#M)ADE zSCz*KhQf(G(a|t+r?JZ9ogJod?v<1@oSu4D(EZm|*yD-E2_}()07Us0dfoR?kGtD0 zCst`pA(k>MU5hz{x@zJywkMRDJuHCMIk(u}C3gS~jv*|aviO-=e9eRWObAekKWv;YMU zkds#|HYg~i1P3sl!C^unloBX#2w+eF6aeLl)jlOE9X{jYez88=bw%8$5dz{ZJgr`u zK2V8*Qcd;@(J_Pn76h z*E9sPHm4)Yv7;nQ(V&t|Y=A^bu8K5OkeMgw4SkpdiYo6kcB#FoBCcY!1h_C6tP@(J zM{c*|b${$zNu~~84V{Uh;CV<$Q3helGi`g2Glw0X zt(7xEDHF^i_}oNyz=%-*T@VC#Jq#xnx5)j(=NKe;I}5DICvX6a1^iR!jC9#|fXZlk z;Nf%e1?VY|3IME;RcEHhGNQiEIN(|(Iv{``sPRv{WOV-!9xrZoLT5?sd&~l)%@ALD zK{q{0@v*}Af*9!$AUi0sSh=JHLD-5f&s6b{9w%I!Fo<}FWC$bb2A>$I1a8gqOPB*u z#;cVwf}#kdGRTLOW)kyp8R?R-<-scQC24H&crh0BIpK(I%pD@9ab z%88fV_jxA0$Dht|fOW)AKIfxR4o{DfU1^JREu9v{9MNWLw258ID*u<`|G}2{g6oY? z-01>}070FDu;IX}Q7SKM>U2UdeFf?Q08%*lm(4a&#G(eQfBv*qeJM7c?coEGmHw;2b+9Fe&< z4Bvx*?9|56!1WH<&u{~_$Z`#VK^AT(h}mEWJ%ag2;*IiWod0vY2OF$u1P>s-_*d)x z4I8~2*$Q$5gqjebdIdG<0YSc=1D#G{OeW>Tw{kGzVtkPTFw~h;g3)G1n0wbx>C)qh zM+?^|)>W%akWM<1Ud0y_1PS1PNN{KkGtpbyg+T$w-YP5=+Mw8SszZY%yluuj@;K9} zw^KZpzCq<6f0YY(v*4GVXM)HdH>UpIDR(i#!wsdv#Uvn**C4Nh;H61H*@S#+FF4Or z47{Cu5d?|Ak{~o?^EMaHj?cpdi<1UBCoV`bDieAhb2-a{3*v8l0<_BN^_B+*aZTml z^d`TSpA~>ZP*-H^YvO>5sc_KEj^A0V&p z>Q^OYAc%x&gJ`zd7mIK_AU*1LO9lVG_U;&omdWVpirMEJ4A-q$LL)R0S9R9;s1^2a zzv{E2D&FCOld8#G12Go7kmIVj2tsgTxL~Njxia4?RSAwl>lo3#*sg4jG`c+1=}-Ks zTOLLgWjF9Ob0m%}nq{hX${AK!ZIh(Z@o>;XSeRE^{?zS*NGYQjxGVW}vRM=S4`Rfa zJaS65)x%4*7(8(?Cd43)b&n|Q)HVbYEy~W`Z~`W=grS5JM~dgNfo2i_Ja|kfj{-ol ztv~Edf*NdR?$)|qin&6&7DK`3R^Fji<5Vs?tsIH3s(CW+vqZ=MnJ7}-KYfBHtrvYH z4x~aqI)2+h9EK7|)C_tdXRnz3E&2Or_`FyWIunfSqDx2(UkfgiY&Jl#W!rA}IStv*9V8_dPhEW7`+TpdNpN4OaA=J$h<1sH(!1?j2-x3(z98NNoe(D-4=nZuNfF%V2^&p8 zR2dorxXCC1!~k&!Bi(|_a&7lAyJ7Rg?M5%~CfomcD1mu7wEa;#77sB7ulc*aT&)A9 zJecy;8vPzX_bx0XM1}V_+1?pIBVLd4yImGfx!4&wm_H{xjk+SqLIBpnmMF!dwaazR z@KY(H9xnJo?JVyd#%^kY|&DvDsAcJ>-u&lYRv!kL)_qfxPcBHaw-I7F(x1yl9Yf2F&%Oe z12cpa&g)2e@bzCvB|d%@bTk;%gNAHQZv!Y}c_u1n_cPcE2K)-QeAlpps2y&NBOGXHxnNh%`q(OH$k z{H9NNQ#hzdq zUxO@J=31BZ1IeSX*Lcpd^iGdse_(Moudd8F@BN_Z=lV3LHi91~>n^dN(aA3hKli!n z)_U2YXv)mcwssc@^RL0X;4Nkw*{IuN0RV7_sGQi!sT>nkW1v0xbg#_n;l0RaIg3@V zC$duOeIM4m#B*h}LxE#t?8?!YeRq)c-s;m3gLZq3*H(FiUoFzyBph&>mk$$wsy9RtH9ZgV#-osp#pZ{>-tM$0x}jMV6socz{4QEIxm?2n_k zZOn)Wvsu!s8h+8W!J22gaDZVVis%F!c2M8>tlKPzCcN0ChOplMcx1MWUV-7QqLT%oV!HZJ$j=Bo75 z)Yn8CEk+9uMv#@rjYig#+dY=e+G%9qRZoTGY}aL0JSX>~xtZZ1xV|1O{$Ise{;E@r zh8MNEc`5%TAP{PBz6$%gM55?T9X3Fo)$o+Yi9EMsFt~f=)8ca%QVTEYk>_^o&Y!R> zt`LlMa$O$shl!z)%}B_t8n&5(5#esqqaER6y_G!r{Y4{;js8_i?KQKfKs4u^@5Zxz z1zp(5pgCh$i^nGb@Q!AAx>-WS$t){wa>ENXea=10dN5p1Y2W;&HI6vBF~$&la5AoN zxg!2Zlp=mR`K>}bwL?c24(R;UqV=5k?$=>^xvuN8z#;OJ1{eui9Hs1%2mv7EK0>Ao z3@-$r=eV9(h9InSWn)w3!JZU$*>e{CjX5fxW|b|SmleWOraY5tuguhNbWz=l*6a|? z@^9pF4M*k8C_L8f5d_iQ;m>p?r9>djjki{$SGYwb?f0CTg!DU=ZjW7vfx&QeK_*d~ zD2}C%%2@QBmKEU6f7ux6m}zvdBxCt!R@v^E-!~ou)_j)fL}neUghYE|zbOe#BSKl! zJLA|OfBEfvMTMZd;QGsjf!bOKuq28 z!IPs(+H#qSm+UtT$9)GEhDtflwdcD?2g1BF15tlO*FSAK-`M+ikh$+@R-I9}ybFMO z0)+yMu?vgvdW(_N`{%{E8ciEuzQxjgRAxfJLy0Y|{d8=Y$PaaKen;5oWVNIfAE0#f z`ut1)%HGdbW~iSvTx#-}XkI3G`}42G@`}gNcT~Of^ZVVbazV&R4AsMWD20%x-BS>I zl)#&}+DDf|`s_R?+h3Z;o=U5DcL|Tua z;`O)^=_V}&aquqTnaKS2fLYf zuxqy>wFIPZoeQj4>`zxJ&Ydbbc8zm)A_hii$LeW2?DIa|QJ(tYyoK#6^XOgq0q%0` z3N(LNskCe=8@v3?mn<*lC=_2&Ucmb@U^t*b$yy38mk=p=yd2ikK8Qw=y4UQsa=;$F zMYHOC`~zsf269KiOWzEa+pZOxZA+i#V;a4MOm^UQwIec~)MF{~2l~b^$u4#1FaU&& zq_(rkx6tI{+Cn!BcT$~Nt8IrOHM}KwL*%w6#Sy{viJufnGC#O%zcq|3sW`}w?R$om z-2V-zcKKX1l+8TXaIOEixQD6a?d?|JRO_vU3o5cD6Wkxip@_7rkU1Vk(bqnn65+o+ z+SMH9Z#GEqDkbFiye=KnvJ*Xlbnm-)Zr4BCK)MOy|A_3rTAaPu9cl95&xuFYF41^` z{tLFu?%bW+u;#nbXu2qDZz&uQ_5V%uNb3GsMc0L5kX zj@tV2_wly${>t@JT3VWN)+9eI>xsU7-|%*<-_yszoyRk!_g}AkSA3f6w#Y~tN9&4I z0zhIecgfYCkbwa{w;t&?0Hv(g84OkUhtY81MC~7VOU%jw#Ft#>;ETm!ErW>$jlF!V zqcWyz@z7uHHzvFEhh4P#CD^Q%M(fi=KCaEVwBOve#)VCg$trs`2|;7eFXBP^f5bUj z{pPwPn`hr_dHZ=(OqkW3$_xjNeSY|~wQ}*wfI9%UJ;|rv0@Dzm*H5OgxCeuC_rZsL zMuAe6veVGdx){x z(lUW`k5dptDQ|)h<0Z{WYQ&FP<8c!MDgj;4;q8}pu}vfM7wE@E5*ivvzq!Fr=y~Br zk;a)W(+7+ON!D1`3_-UQ>N8+g?h3M^xNFTr7oe z0R-%hG*}lefp9!#$xOj>XJvf^pXYryzrGTE3m$}qSZH3w#c%b?@GD%k-My|VVI$pO z=pEaMPQybmJPMoLEsroV%$Dqn{h`6#UZEt45@Ppabmkw)XB&|eZj6Nk8b?wyc5v}G zh2jQLM6vkc<4J0(g;LmH90Li@?`FvRR4(10jyaUzlSslQpIc`@g_p75C3gOW!I|9` zl%>k{`#v~^-1mH2P!M^}>&hSH0mi4jypIQD1jI<$`>Qfw+fCo9lzo}6?h-L~$DXT? zk(Gm6*fNwVE{A?UVOjPFLJsON2ea};meF>GLPxR(nofb>4w~VtnNje{O{AauHjmvbz09kZoN>h#~g$u8&fx;ZVnKxlnSj zYcT=U*BQruzr@%-QWlG>qSf?yx0ctN+}l#i#%6NtV%Ps?>7QWs;D@F|Z|x!!v}UPI zu3#%ENbC9g96{QKnBOOQ=nHD+NM2DXp7dT-1>NOG)$39Wui_rN3mozd+fC*;w**( zspoA)%EyF#R8d8POFJy{1dl^EP29_ZA}O%FJFnV1t(HjD%a1<^l91kQH=}>5@jHK* z!FZ9-eb+B9ySr@R^bQ7>w1}iN`)FR!J80SAAN_Hnhu4l+`?HH#Aj4CUD7*((l);yZ zHB)JL8$e*7G%sXxR&D)A-(mD#q-KAU|H78D-xZym@iqggaY7pLrw9M~BZsoj{U)ra zMJnlm0O))F*eASLxWL|;z6M=@Y zLYMbXM!A*7bXEQ)*V*Rj;MGj-KR(9?M8<53hTgWwOJrV?+c9#+^3=djKZC5#PqYbv z$3bZOY<5;#Bi6f~CgI-uF@+MlIlqYYIIr0rJ&tpoYlG`qd=%e&I0(x~-4)gOBhZty z!(#;id>)6V3>PUI5h+Gnhl z+Qxa`bl!y~`a7j#t>s&-msGc*hs)0IXZB9XUp2=C-Z2E(d}PihO(_4W*F`0cpVL({ zeH^3`zd*t`7*6{__m9~JE z8S1}6NS~`JO6OazUaHTb+WGnOH?#IM-p(|xE0m*4$Fd%Y^i?jSRN@N?lc-HZqNKHf zNkBKcD=tzWJ#%RLQDU}bRB)vsL4J>SBgyaq}1S&=)I5sv;vKV#`Qy!$;yU>^WqeL=aI9xPYU zqN9RYsK~$sF1dYu@nbO)0UDr^_ZV2cbd`VmZh9~)`hX(k(k#%K8j1n@V6Xb^4Stu- zL9;3aP~A;T;9!u<*`++~l%5ujwVn@c*6)=VE0d6CUaHi;!6Nr*KHIrPt{jB@s*NhD zq`sPs^}j{q^*^}X!K(+>c>sTGV8i37GQ;>I32)e|oU*C4uRlO2V^_6q9q$m++ua9? z?mv1fe$vzEL@Yw%aA{XGZYQFb?;G1Rz9j+x-7)O&7rh6@=z3gV~g|pPfd|Gz#>ZmPYSYV!WL`0b*c>xsJJ~iL5Gn z5q@4-A%}=aPB>`O`=X%(URr+D$L0|lt!KBz1%89(I(Ck_1?HRu->|mN?1aDGFLadL zPabznmet#=EjLXW7t_q)oB!v)58Pq1>vm;F0O^)_2~m;dE;8N3+?;a{!$F7w>uF^jLle{^wQZ zSFwdBLPor5XgSIat6aBY0Ud!yugn!VxU4dpS($ale4kEQTWn$B?hJTdCX(YbxzSs{ z_PHx{NBa`I>n!`p;`{|S?N#%}Ipn58o%Ooiv=8Qsb>M*;fUly$pl*a-Pf(Z;c3`Y6 zTqluf5YseP4|x)s%VD3H89tLA!jl$uJq& z6cq$Y%Q4P>wHfw3P~iwW{#NcHGOE3B;Yt6#>$#aFhGm=?{{oxhA+ITYiz7`AYm3kV zpdKI`36%Aq@-=@caMjE{HI1T^Q^WoYO{u0Nn5t4ItEqTm{UjH{d9fJ2fLI*`H;V#euzj{Z zD|}4iG*``+N0bO<7!hZ!-VwC7Gj}4v0Rd1>jpNhFfh%Eq(#M@CPfm*ii_2^Nz!H5K z*mA5Jbb26(But|9)7Pulpd?`vTb;w?B{I4U3z0nE`{Y~F{2NN5#>a~N^1eI=wP3zz zwzMmA`QU3AQ9{+NB<{09!4NjRq!SG4WPMEXTmOXjNa4MVP5`v3h`+cXU0PVVi`W!Q zI;y= z)Nb{le&vY9eg!4HkCABwKmwF(rd4$5p`1~+IzK<&m*BF8KrzVBR+{EB_7gXg+LygQ zX?@`y3J&+dT77+eJPEu+CmWdc*m54eLwTa`XU3vK-D=09%8NZeaRmNWautzQr?MZc zEn|FXgzm;%+y~^}U7FKZO5v-PCB;VkzL53vR0vJ9c?uhbDHE7aQ3AjUA>L4n{m&nY z&#x(O6TOOQGxte-r#imogw2K1<@M=oRyX|led1RX%4^*=&ZW_uPY`enRqL4wL+i-q z)9>;o48v?tOT*whG@AR$RCPS`T5QHZ9JMi~wubQ|xzGLyg%&|u*)N=4E#}Kk2}t&M zeA|O&d9?*!s_H-&0`T#0)1htS&U)bo$awDLPX4(Pc8>7dQK0PApa|WnBb4xIe(A(5 zVwR*rE3g?UcvW+{O(UM%6Jdqy4~R5tzW^7U6BNKJ$5Duy6C}3HxIA+3T=lo}h0Bb% zj}rTW|E7qkfR7LXh#U;r&OW?w4ggBGmBDnhHmE>f^Xch$Dz_N!W-2f5*We_R2Y4|V zue-4{UNo?q*WF%mDtF|E54#NxyxOIIhX(-ZoCT~$dCF`wGSsms)mIc^NZA~js_jYsTXwnL;Tklc;rRf{WqL-Ruk01!oHh*k^NERp8k_T zmzS3WUTrr!<1gl77EKV2q^ezSisrY{V0h_e4YMTCyJZ$I`h0JuoEn#!J3?B30Ogb= z3Sb}w<(5p>SUVoAABg-)k*pk2)|&iIQbNAHzdr$ABU;UZWuzE-cNsqq=5Y4Rh^)aYC8se()hy~}1 zU&|>ev7O0V{MruL&oBf;I+u>BQ@bg1G1zKoZ%QrpN-oT5zFs!YxR63|V~MyR`FN_(Epn6_^PNls zU}&}8*1m~9;l`@|CHe4e4;Ae4m_>F?L;KfKO6#yks9#{BhoF~!4_BKmozG^YG688B z|JI{r8G&i;z?}PYYN&F!#(o4u>w{qB99-?M+8J?G4v znRniK$6?}b>HcfGTl5I&$Vdi_TUYrWNKf+<(EfFzwzg{AIAk;M8TTrdiYfyQ$JKWk z@le(U+W>Pl2ipAn80lXXz3 zMAakop=uWIy1oq4Dz_|CG3sx*Du^W!7mrBHPKoW07HqU5lG&S+2$S|Z`@%$%ua&}9 z9QZV+Q$C$_H=Q;*%`3=Drikt`G%uArS~FW@oN5Z&-Faz%O1QY{E;bfVg(0 z4lW_#Gf|o7moCuBQg7ECGJYTX`34){jnBodG$yp!Vd9&7am-%^e5>v4$6!~H-tbZK z+~Cjx1M_mM9 zttdY3!Yu*^U6kp2$m)SCS!#(|i8%5nT_=a@{=%cAkKI+DQa+Y#rleggO~zKMMxkld z!*=w}=J0qXzW|x(8nuOMrJ3IY#c;$WB&L4+AhihQm7Z7mll|#*3hK;;uUj<&tM^!=X#;MSB>WOFN~-M->5 zhGI7Ehbo>NFe<7+tq%Tzugu~CR`~thaCLw!f2(m~R~^zLjV%S&ALVOhNsG%8Aza|K z@0~V>ikIseFT7PW3#s?4TvK^q_ z8k9>SxR!zSg^!OC>x(S(gw-aaI5X>q?SCMx_vy@ry+0P&WHk3v+~%Hd*l*6B#T~PE zog+p+txkj#r^T=tCNFr;BRXLIwzU8>rr!g=qMDY524hl=;>y!`ehvoSabW%wvUGm9 ze#ZAh=51CTJdvVeD@Yr1pj|?C#2>9J#ZhW8>LZFg>Z(-Rx}nR*kja~;q@jd-(@qCn zjp%U|cjf|Ss^0_je3M_lY3hW_gok&%Eh>Hl0emu| z8Wn_g?g&z6$MYg4bHVKI$5_p5D?CagNj&ryDswt-sTJCon0^=zvc91Oti^q=&wSRx zD4UR@A{vkMTh0t7cOk;u1(5hJ8@xZx)riK!W6-OGdb`K7vW`E>exvS}n)jwzo1v*`_-npx6 z2efkr$ib{Vjr4x{6$G=X!<`^N7uCw^0K3v7U08YB=q)pT^Ha)BtNMhPVwMX=kAK) zSE%r2V%0i-YA}=l1jcb}{MfJ1*C&}Qipj+<6D|G6dGiI$^_NIjOtdOSb|>DC=1Vt} z{G&s^73391Muzee@No&IO6_L2?yry;qkzrAZ(3SfZLRI?Ufz8dd#-*P{p;$*d^!rRy_y!cmbx9BfsZ1_tGa z3!eByM2I~qS&Up$_M>aP%OAiVFuYrCty^S&iq`EVNW zQB$>5UPtHBO2_O#kr%1^>T$7pr1`?`uv$Ap$tqpEm!F2JS+7DP`t;Ds;&^1&O}{fQ zdUsCi*7S6~<#Z6&v7;l^H*7&#$l;z=gL1+n$QG-VFIfqRs)rxPwj2P@f5p$_$9^(? z8~V0+>BV_Bdya2NdlND2hq^@nJ8#daj$@;2qu)I^0UKZ0mx=cu@WlMvlsmkS8IBcU zQ|MH!NY`#(!9Ev$Cfm28U77b6a$GI_OQ#Q9y|xst)+a@76OMP1z~JFpI;ofDcd_S0@u@@NT=?z5skf_)I$1q)h>5rVnv>d8X%YoV*5f5NjEy# zZ)`HW=oI}A4y6WvO1Gj=glTj;WiG+N_ z|J<(#^B&p(V?K@K4pg~z91l$~^<6&R{hn>%Yoncfj=!Q% zTa80Y4xwE<>2ajT6c+=e#K6zgHv#tht;X*-E@^?XYx#pxdVuQIqqTO+Ge-}_y_#o2 z^lYE&(ZXi1d052T#f1ReFT~hX9s4}}Bwl%0`)NFQhmtkPZvoT)B0eC1)4kf&eEotH z*V9Ikz|QT)=~aUUbApjP2;9P;Qeho9lJjA1>ilRB zWykM)$ZQ3{da>8{ZqGLQE8a}Vpz`8f-@|CmZ7Er}?_#P|Hu2s^;*>gUo3Ah9W;bq* zSYudO=RGkZyG;ybSwp8i7Z(B{56w9`F;v8#1Uz_E#=M$Qc^=Q87fC?>SXHwKe`~!U z_2QFbm%}kj-X^SZH9AK*4R}s%=oHAf{Qgh+qv7OvJzY>~t<|rflzaA_%cF0&y&{ip zMvh8VvDL?ET&=kA@j^aVE%OZYf8EME&hHE=n0kDGjH4LYRFTA05MotOP@+n%}q{1s!YTF9Fr+Aso zvNA*rBBoypv823Lu&3C0fy48OFs!2Lry^#Cuo4Te5bNim5f2@|$pusUeh?t@bM~Q! z=N&Fo-}rWi;tcN58*T{v)>9WU9$z(eTlA~xMxW0ziJp7)lYS9o@Ea!A{a z+?^&V%Q19u(`#9cJncfjJ=s)*=c## zMu!u)WnY@5Z^AN%1)i3B3;5Lmu-e`@b~3V5Q^!1m`_ew_2C7|ri2~jcxjmQD0vSYb zSwVhhT&F1&7lgbMcvN*CG#A4`S`(0Zb@Qxjqm2wqt%oZ^Pj7j=;&gFYl%PN-NB?Dr zGl@>Tv|_3a`I+>^p}wjH%k7<8#v8Fe8rb|)>jTGK895ogJO0-~f^Ml9`MdNH0Ac@^ z?{A)ph(6KK;^s>2Kp>;*QHMr#be_Xny3y=tc_h)MZ*y+WvE9AJO)_0Vqdt4=)|k!+ zvr;z*AcL!1zCf73p$}*05!s!0Dsq#dCRbV>zxW@T0v@+n^^aS3vab#o5PRTRF`N~# zQtWxQD)xzO<8znMZ1H13dW;xkYBvWb7@Vk5jNfzjfj7GB(#;clG%+!;rG+ng8^KH! z)`c&+!zSyx1IZHdeG9yMyqIw6ywvLCovzd`J_=ka0z72HLh%*!?6ZW%s;{SniSnME zPNTvyi*hIr^1)5_(p#}USL)pvi)?)T`t%@jpU!{s!?F5JN-(MD_Ia;0d+^Z-Ort*&FbA z=)#*v(o(ah7z|`2)Q^&M05lOzF4LBQWEWXQPwn9WgIy_&vu|JgkoxTWd@79yM$!&j zMh0StpQ0CAl;~?ckh9y_J93=+{$9YH=NTuzwxjKER=)|d2UNkc2?6x`Ecb)d*;=#p z&)0ZJVmMXaoM4itg|<#apf+Wfb}cv5Ka-X^e3x_qed?P#+cVg%^$rt&;&G_=u$_@d zMqi%bf3bTKM)C1oy4U##B4vQr;bN=Zj-QG}t>66}X{CVY(PH@>48dPq!u=`W;DDcJ zn*rVgLX(Ie=!v`N#dg9MmHk*T_&Y03B3~%5+V(3Twh<`cYJ98Hsdhs1#g01}9`#R9eGo6%i;I?wS+#ltBZxk&)3P(dD%8xq7$$X!TWzgB1DH zvTpi)UvRqDB~aFd!hZGk9(OiRBLuM>9W}o@kCINFfu#3UPCG4o6>LDKV#I-HqhoSn z@3-v6f0^QCb~rc)SIodFQf3*DnT%}B>>lsixKB+}Vpt9W&kA_;fQoq7N3&FhSrF zyt7ihXG-)xaG7@Ams&|8arP7R4W(M?q~762&P9cL^YiPrKV41y660VE8%b4t{iKa6 zhaz&JGE_F@eDVG&yOSZ7BHCtQ`n1GTL*ppBQ!;_Es7}d>nK?h?4IoaxN+rw55K&18 z^e{a+*;YXKQIL=%8yFDy=H=(nsAR;SVUt;BoQ*A(-&C)@2Z7UH)UlF?+V5lG1c&fV zBa2=pp#NvR@ZTBi9T#_f6GeJ7)Y{MeQ+?;VQ#A8>x`TYpoR%ji0QiuUH)ePGa2t{} zflanMUrt0{cvzFihRKdx%uBKm+wtW^ezQ)@(cH#E-1tI<{0q4kNp!NsTq#K}Wb^A3 z;H#EoL>AA~$DWOUm5f-DC(>MPSqyR4#z5qw((cy0><)3hVGp2I?Vd~wKct~9v12IP zdeNkdPsT6vv{I4u_e%WxS^@@@5cir$B@=8}P*9q5*QG_e&mR0BsYy&e1-O8)&y)B5 zDc&)$kEgyh6FmW)^VpP-m$U+g=H*(Dh0Cg{OduZK3b3)RrmORw9t{@_ z0YU9D(Y6pEa|Na2hnH1ieqn9=4gx0Y0B0z+D49(V%#j>?7_D6npo-~#eXrrm5bW>* zpl&LR_;=ucx6ye?MH|T(e|ABx3r>tg+5~H`CVO69TWP)i2*FJgP^IjNRI7x)5kJ4G ziH8%5Q4^tN^A}lGYE4_`9>sOhsk+mEjhvVnMFD16YmD(PK3Y(wvg?dXe=XiN8I=rD z0I2=kJXMNx{{fc41OO`RY#_o6x`qUCIA6g2gm-NezK4&KYt^K@rhsnn456u@M6SZo4bphsh)1I;k1=Q@;l;5)X7b z@22-A3=ItT{W;X7`mS;U&f+b`Y!}=Qb{|x{U25rMH4+-6&7Qu0O2o0uco^kVqkGSo z+X-8gG6xwLJZG4gFf-MkOBSI*!a>U|paH(Cngg(rHHRGptOg6&NkM3DjL&lb+&~+q z-``Z`kNUsY5ALls5l_d{_=0SbR)-yks>3{=NP6I1gLHB!ooe(qJ}yK? z&Gr`vNhK_}%%D7LCz-IOOewC5gQ@0{mfgwH4XsFIQOu`94mOwHTs1R@IN~s0vQD_1 z2-E=QavcXDB-o7qnUpI09Upn=G{;<}>lF0=o9sRa-Sh&Sk*0pNI$+QssL0`p{;}pW zvu%Ed#v#Hrp{7|hwLev?BHOlCn|6M6aD^}t!B5$Oj1-mjZmyP_ibg9rB@iCwRJ)2i zpSE>-);ppsytcU9T~=4O`QV+lIXo8c>67!yc(^Q zu~>XuipSt_@K9ctzy6{s6;Nf(zsG#(*ElNvf2M6sK|I+Av#0GrMGb%dr2w1E8Db%q zHYG=o#*YHA=t+2ZSp2Q9Q}x99HQ`R=X4R?Q$`>y@JnCWn6Skb3-1>auMrJYPyB3S7 zvIuoz){f34^U~wVQWqf~zMP+FQO}Dy43f>6Wp^efP>aIf)1l!oA;={liB4gCPU*3B zb4VHMG8Dg;=MVqCJ)<%xHZRdsGwviIQ`JU_13ODv)~XN@nLo#2+Nsmzuk-h{jwGy; zE)b5D`!hz&g)cQYJc#xj!`Jb_%T;qq89)-1p;snKL9y&6B_WLruWa*hX9KN96&=my z6-+M8Fj(ztL0;x1BE0FRlOrxW+$pV86oNzdt5Wy~f8UV*d_MwpFZ01uc%Vt9>r6bF zxore0y`f=uM@Mv;oy?C_C@g&5oUHUkil+Gmt2uIi!Urgu^;ksw&t!9#bLllC9LTR6 zy-tG8Iy&aqJ9P3G{g2u`q4Mmdqv8o^j---JQqnZ8U(pTZjxKKCW!tw0RY0m5h%eTo0VjWu;8Pw@Ui* zCC-a=zDzoJPPFpYO!_Pw*Gf%2QYq(Eh*#+6zRSIH`;Y9ztym`K$|BK$2OPZE*Z^Nn zil_6rrLnT|d22`T1-Jg&AXho2g2Xq{7R1C~F$Kg+Cn5kIIRJ~2|8CTn5gr@(G}!o; z`g7z21YTM2vWQcR!O?L`ZE=KytawW)z#->XhqbuweSx@N-OB`d$B=P-bQqx=@}6bz{tk3SY!G* zW!!oY!X%iigeE438!z`lqA=kn2<)osv>B0vqo1C?jRdIT{rAM+=cY(A6H$t5-w6Qr zN!P#l)$}wCqM~qt{+Az>a4rD?UEQjur+q^9BN5xgK$BcEY0=JCk51FZk%ZJcLa&q( z>6l;#b0ggkrjjf|>HX&r*$`)OG-UK1T&AMu@hZ%u&wsVFb{HHYs}zF(TwUP*56K$6 zkq8iAK!|hIR|RU_mk}jJxd{kym_a*W)J%0r@*NACy`##FX%@XnVg6SC6t)Bw-U~US zprBp~-{(MTej)k0)Hb^me%@wouHjrpJy~fJNd)sAG&Naq0FL3b0OGnPOFF-Wb) z&)CLc1o)H87A=VeDlEKOA(UK2J@}LS3im%xb;xkJE~T*r0$53v8zd?zPOgswE(!8< z(MonQuh}=GrF>Ji$zS)1iBym3`mnS2%GR$sT!QCTaU+oK(+)Dn8_Un)LR85G1JKpXB(!WprZNA+R}2s1|qg$*s< zp0^>({>SQqoe8+_H_8o;y$EY}05Ty2G|{cwb0qsnWUxA6E}Y4vEQ^kY%E-t#+hse& zRxr-M$H(_>ab#)9g!_d!^YCya28JsqC&a>1YkOgxG7kZ^I)O0z9iFZMFve;uAvea3rL(o8QaFsGF=mGG;MWw?$`w(Y9} zHJ5Z}<+ydWf0Oz-d+pv$gtz>;z@ku*ljtV`>`PM%;;;z}#AjcAAd9tFQn$S{obPYm z$)u$buuwpw&Nf=6pvY#rzt$m^v9@3S`tP>Fj5^F=*g22iF4{fCt=Lb!MO)_6VW*8A z_>r~*0Cfz(O-UQBC`X3;Xr{~QMHw?I2uU&~vz!YdLQP#rLGweUDaL3HZ<@kq8yo&G zEM5G*e8wn_i1+*{{4)q%h`Wsftl+3jXDkI)E>SupRO*C6SNEa>jX0Mf4Ha;vYmB5K zFHUfHq0Jf>byJOT!MHW|6cbRXg`rpJqwi=9LC_*IdKf(0(1Z#_X9ViFEyOIf|Gc$^ zGYp_Y{(i0P(jlk8C)K@aJOZx>;}_0z8b3z8XZ&K1>w4kLJhfZ(;}-4jVLD3{viX=v z8Qr&2kPv<=UA7)EI$xVXk#O|&N-a;xVRucEdPim8Pjq_P*!5=iEgpCw$9(0v%E!9~ zeNmt&ktt%H3cv-$(KH{%l`c|d;x%tJ%J>+Ci0`(IiqDB``(RFC1LkxB%DII0-Q zz&OE)RQX!_%r=chRuFtE3ua3$8A(V`K_xPfr?P^-*w*cB>*YiWow4O18MEewN=Hj0 zl0@6j^jMf{5@@bw_$|aSR+_TC=F4jGJpZG7^=k3s%*op$e7C&ESIe&7o5gWL_Hoql zvy5WH0rQFN5xwZQOiXBhb)V9*lZD-ORe+O=GfM?rrhk6nhA0v`DQ@KBW(>)#d0*+D zLGQUTj_z;2gGyB3_^U9r+}kI3)ft!4cpvQ(ZajcMeWeF9^ew|Xb=7SgtCo8|B_&bs z>{^eMfcO=hrPrB?Y=u-U9}C4%!NDv4mkcM%qv9{@03 zdzvM1qazVNJvwY^iSN<;a=qyh>p$wR(-qon8BBU?qLGZ`4t@ z%{I^@K$ZYy>|WAySExlC3?iM+lGU;=8_)^UtQ0{cF8$#oUUci zGyq_F->%gA442;*f~Fj13(&@e35?%>K+a9P=Q6$>KEI6E4a%E-Af9Pxtv9UMamlt( z59qONthztc?o^^ACZ1z{3lH00nz;uQBmaATv>r}+v3tX?J>A_kj|qv0*!7!OUcWBa z;ub?i!^Wl*@@cTjBA#T6&oXNmn7FdYpw*xK@yhk+sX;EKMJZ3k!%8RY-w6F86 z0Qk~xh|=!u;V83eiQW7Au3i++ldtHWeov>A{o`D(8azO&p9O_sUUsWLWu&F8K^6RV zA`einA3_s%)>zfXjUNI%h!F>Q@@M$Qz7PDD3(z8%@R-3nqJy)VFWfbxRD{qZ1px6X zasVF3eQqG0ThXBBZ?({zJEF|8w z>4GZNOS`q;M&1*Tt5Ob3N&^XWJeO^9MrerbjycU1+IlX2L^IIgtm~OGcblV5nU$$O zZIYimB>c=w~PL>)cW{=s76 zOoWDl1b3EMyjgHxGX4cF6=Lcrxghq_mmnYc=`st_`d*Z1a$H9hxk&uL&Tts=TF!T3 z33$fkeS7=)^XCKw?T3aR*4%mouK^8>M0Hs;&-QsM=D)F+_$Ms5x?_AihuiMh&5f7% zud}UTE-tS9qtNiQw6x(A_MCU#9}fpE)(rL9$%N{z-83U#3ISk#D<_{M-}{*FdO-aI z2XoBR!{w;%heyXQE;ZwXy8-Cb%5cDhBWifmRZk)w^7J$tNr`}O2T-P?#T0pxv1EgSA4Ak^FU}{teQcwvNIJ9SUdWhlGs{bT zZY}(&p<&Lq~~-4dUScx%f(m zl$Z8W8^&ka9q?#iXb5jR%~mU|$px$V3>OT^j8&G{VH-gV$t_P7s#`qG2V z;VJKvH=_81DJ`a8of2XF89jL6D3g1Q~eI zh~ilXw_iuSzu#Dh{W$NgBnO>*HLFuh&*&0qe~4no1=07ppZdk81383kT$9`IBX31i z&}uo?a{~U>1J+B|r8a#+enRqGT+EARdOosLQddyI8t2}QSmjq9O3*(XS{fkKA0kqf zh2k;c)>WLU%$jNCKo1q^(C|>4D-{wNrz-NlxMAiKtxSx$xj8q5B=<$h!AkAdV~Ap4 z4r6RIuU7WMeG9#_XoqqohoqgVC3Wg~SKyBG-(_Bnzyiy@&mV%0u6eb~k+ofiS ztL=hTO>&x13L$y%u&`Zvf76fUh~;jz`wSdvl>Vz|#j zSLvk7l>~yQa4uJSyyxcXDf05_zMC+ySK~eie!j3RG4}7RHLS#URzfPNe?B=ugM>>j4=9@>>tDSS;= zAl*-Tw_DTXgI|vh^cg-`y*4YkP3cQ$d}^OU5o*UIcU1>RCe(Wmrn>?_F81N%P|Zot zT7F^3?*gg*-RUk)V7C`VAq_XD%k#d;K_sAw2O7#`);{^PPmB6vtLLSRXpG+_bSmSm zQ&~j?ciT(cyoL(5xibP$>t;toG`0SlDPi@0v3+{TpGd=I<+GS$!Y-T3ssj2-Gvz}8 z_@s`etBM^R)T1oN_Rh%WjSc>BA8XKiXTK0j8(T{o$w4&NU%78j(+}mbbC@QIEo)cB zKCmH$Ylm@Q%UFCnxU*YeUvXSn-iwjtm2MA@7tU*CTi9kU3IIQ6_>1{7B;*ab11cak*Gf2J1ltY2ocxspv0+sQTc)+H>nf? z#NgF*cFg<7#r5NX^eX>)eQuH+(wGI?;9T8P5ysCb0V}$6QuK{yC69K>4Z<9TVavBY zSy|Cmu;nzn(npPnv<>7{+;uZ2`UooatXq|FJ@%jEL zQy_qGbc~aFY`H#&{AQF#|iQ_}9|Fc)lGD4vtsqNi2hAPL#d_ zv$Y9yX{?$NrmE)^`9%L9GXtXajSWhl-MoI0Tiypo7pEy9Enmx>qXr?tI`_)$^bAEI#aFw&&-V;21g70tn^C|L6dpsCHs3Ji=WR1CZV*oSI``T13H!$^X28u6Gncy-S#+!Q z_t$5vyeUNH#fOiAl|4L9$+)LS__=rUwd)1GO5niUb}c6UByD6L-p<3|tfkfuf=+wY z)qIU+{%tROB=U2f=k6|EIAKz<|z=ZVOGH=%#1D-t^PZYua2hwN=PUpi%7I z&66!0Bgm;^(5Kwpd8L2Gh0dDmIb~?irj8RL&B4Po=nYr*1_wMY^fhB(VxBxalUE2`B+=er!TDKPg%a7yw1*504MPBhoF>Qz|FoB)7dsEQ9i~V&S2Nd zM~#TK*3Yj&t6L1$6dc|t-g~w0UN^sJ2=YNyyVWQ-r}07 z*z=Y>hbr$qDvCHN)7^NmhB&3IX5x!m^g3qgRWs|)12 z$aPhf08flV{J}xyC^(t}e_QB6ui#YzDL)X^w z^LrS}lZcis@VQRbceJrq?FkQu&pndn@uO2TNul^I7$`)#Twh?^i7Vh@=X-9xSmStp zm4lT5GM`z+qJ8n=!5jg&J1LxIlfi!G9`TVHxEqV%Xe$`VPslffPef5)uFc9&!q*3h z9xv3*uzsSkMIj9y!ykd&$ia)G{6`#;uk*!<4~YqaBKo@C7a|MFBl=ZVJ=XDX`m z*f{;F^?5MleNz%TD$vr`*u9^XLc%|vKre4OnvDstcR!qA@-CiWXY&H0l@{Xc&jh=- z>ThKP7kP`?n^7;3*CGTwUoDJ|R{Mv=KpW`AQD$Teyx5AN31reBAHLwxdi0DpnU=vK-z^RNWj?JCc*?;y~k5_mLP>QEm6~j^A~g z`w{tH+V&56UNaumLIx|XtbF55)$rDpa)(;+hE} z9P4qx@+>h$xCQu>ZI>(W^%T_&rB#~i!KPK#&<`Q7GC0P~t{hwLPx!-~Do>(VPk(4g zPT9&rBQaTyBwDGMtF7%B5)!Eao5u+DzrA|`rF2QhQa#B0x=h|J2Z>ZKo9OERnKaHj zDjo43ZihKdm7${q8ackB%a7~>`=~HIVq)U>_;~GmmJqw8rjbB_6{$@bHSDBB{4g2G z#t6Ie8Pea|WtkJY1Ak&}kddA}L*}g&{PNG%;iMK?TNd<^(0$v@>SvFrVDOa@pxpti z*gSR5m(^?!IPlO@3kPEapTzPdduXU87FG#eULi}m3HV2*>h#aXOE77b)4!vELbKt` zx_^B-6?de;>n9mN(%HooPTBh!YYc|;Q4Rhr04AU%(dmAJ!&fho%$e1hWuXNcOEj_x z@B)XbE=__YQ&9pEkjVkzhu1|zGdVuH^z*6nnPtu$GiP#r=IAHr$4BNjQ&6Sk(N0G{ zKgT+FYR~T=gFbJI59H+FxS7L*Mz0thUypXei*Pf!zkh#4M!xO5$11yzqmv!4tyIe5 z)6&!|nu#QM_n+eq*$;glvjxC`?DE=UaFAp2dxWV-OI%0OCKk$d3FeSxEa*H(u=cV6{DN#;h< zJD(N^cG{I&3lt}|NqA3d;F~GG+*%LMGckp1-?Vsn`4A8hz>m*(u>Qq=>?}lnZPAVr z2TU95v;w04!qJaQUJjxub49?xQS}E7v1gqnA;dC{7#nGtsw`T4rWRUK(ab2bb84O7?J`0ZvnZ?D*a?Ai!xwHxazSOm}Gi*QQdGJg{!S6UGSB zTnj^hwM@jk5GowWnD=~Eq9EW4tCl3y3xI~2jLGx&QZw>pCT+fhG_aG&VQxDOrrv4F z1mML8*D7H#|A=%4lPK@on>V7tjJPs^U!sOlmgV1Jxl&Vw!;xd<<9 z*e_(9xfyw%jUpRA)Hqt{brFm1lPAT!vzI% zfd9W@h-P6X^Q2v)CZYUJau>C5C??8ic|9V@clqmpi=F~`PQ>s(THTGa& zpeuYsSKsP>5K6F!j*YF(2=k4Oj`@X8Zu~3W1qjBEccr5%R7a7m-pDME?Z?_CP6x=mVfZUJODyPfc57Hb29XUHSQ@PY<`|hhrwpjo5qTx9@$J06H>ffS=_e49g;;L`I?e zbi!(JdHEB9PJMu%&s~S%ttH@ZGN2kO>}gzQERpvv`S^abk)XBq8UnL6l@|g5yMorc zs~)i{k53hI{(_z3qZ#QF-2qRP##q_!^daCDDLTyd`*^0u-pi(X$b*|fw=xKr?{3=e zrSOK2eQ9VKuo6*ls;{y}t4HzOX$!X-5zZ6jVKPnmXW;ffd!MeQm z0v%GirUvTsxNc8lO`C(*qa91Dh4CD2YVKuNGTZzHAwPsA{E|BS1!Lmll{?c8P^4_S z1G!*D_a9Bx>=6Ax0M*GfuQ4eF9ij_bg?B5-J6A2gi{pkeNNg9!I|DYMr-hxIj`Kph zgM1l1JIK=+G(+Tdv+(`*o;R&@*BvsSyfMUDq;1Uk`T1{cb3XrbA~S99b_CsmFJGe7 zKal`bA$;O=mrb-jKQOQ?(LLNHAbR?fcKd64ThQ&~^pClPEwjD#PokxTEt1LA_tz!f zM4Kkj7;3LyN&rZWClmm{2=-KX9#6-EoU4Why8H%YD*w2hFXg3^Rr};8SE>ge0CAz` z3euobHM6!p9p`pe6f;?zZpXnz4ce|iq8k3_<<*jsGSlY1|JHu?jpva;U?42iBfxjA z7Bx`fnve3e`V*fT$l2tu>wy^q8GI;%5iq-`QyJd4db7ujDj(6Rf&egMv*{!rxu46h zE6TkA=;-^$zBYH?_Z@pOL}MWU;Ms+5F{GQaKwIOrFxNIL;O2HR+=jKWibLq`Cjc}! z?75uHvCZj@=<>OaC(&c(AMPeY-PHPgmAF^|Hdz>lqIsecm1vbCP_m>Mo9MFn*ka z;m-uTWp^`6aG}Z{WoN^n`&d<-{e5KW*MTzjaD_}W8@K}DFMc!pczIMH?+cnh76cb2 zXw-WfG1(>n5fprKU)JH>wu<6^(!~GF@eFvE=kNjg0rK(b1UQht z_5dxuFwEu)NNO`yT<(kD4LF(_dUQ@U(s>o zKHXj{D_{lH2BZsgqJiO;zk_&-AeuTsAqWm0DxTELB)iRb9}RrQuoSvj%FkH2b(7Y{ z_Q^y1-%#ntP>-J`whh}Ad57W>wta0e(T(471e?x72P9zR$Kyo?IQn_bW^k9h z8s!23Q;BW9NdIkF!XI@^wkCmi8YlsMi{UIRRUs=xY);lXv59oKr>KK9mZzBU7A|`h zIFa&9A>wjA$*5s%)!SXV=c)iX&HG!xX_suR5h+%-)8?0-JWtz4Y_RKltMY;FKz;Mh zNPuPoHTTqR;*a%Q^JPe>T`&mH`Tj)SiW6X$ij`Z||I}f!(yxvqApEB`;~k)Dw$;?Mh&l?oP7_4UA#G}KjeiT*g(&`kMDva8_ZAyTIf zTuREoyw0-6D<2VeLoh>_54@-zFl(=-jlSr7;`hl8R8nFUD?_pGx;oXW{*8iMq|I|5 zATshhk!(E_Bck*)l{4(7@7(H{4G|m|c)FcCXTN>NEwCJSzVm>sCghmO^G39eykvFt zDr@;kC9&yg-`lrgkbN1yl!MU$;lnAmape`s;-ARvEe&y@u*(`saEp7u$y|n7cBbdC zkd0^5(L#SLAvrt(%r~C6?9B16sE*x8;q@Q1TB)aCHHf@^c;i{#xO9Q5s+aryH2!SJ zc$?iuu#JA3;O?p|PxG>Q_s?n?Z-c17>zn)H=%T#J;3co`Pqb1d)_dPtJ>aIF7s{IP z^m}M1!eOdSX4FW!z)si3W+=!X9=^$oikftTK2=@K{ilBK;PRZL{Oj(pvMu1z#J~gEX6O_#?+oMBc5gVJGwXxbMkjOFK0_7L?1!Ig57%s*jif4 z#3?jDQgM)bHDLSud=z z$}QJuiSiygeB;z*P`BNiLZ~Bp7QXA;dx6ccvbemkSN-LgQe}E4^Md5N{Ch>;!0i$h zVxZ$*`08eb-H-3MwOe!}#m%@qNQns;{Wi{@w-B{j0wv1cs#Y+f-w{e(cwrd)4HD;IycK0y~d!Yq6icT2>*bBnj+f@9=6)&d;Ca zv9Can-HZO9j&xF)=T}$4$WT@@^#K%jQ$!PC5}k*HPR{pV~$2t%rr16d|%Nv{6)E2gB0WpF*F~! zJJjb9rIRatTyTxte{*y>;CpohQ#P6kERLv*#q#bydnk)V@iwy3t%{6`kH;k@_J$KE zTc#Zr9<0Q}l%R+1c3NqyLnZnH?-L3wnc_M6`OTs@`ib=~&u0og`2Lp*Ff{Gra!M{> zv>qu89|j^X?D7|bYU%n5cUtf(tqu0JCXw~{_*{lzC^ckUtmc{!i*kncOL`l{|8gI# zBJaG%{>bLNU39-K@;Ef_DkjT|xktDmA+LO>dp(h?U^Yrz|Lyv$k^#d6K3e`)6lRvC zzn^kc)AyOu+1rPo%}IO4o#XA<_(1ZJpDPq5cl>k_{kH7VaLGAJd8(1gJm!;sBtuOQI zCP|~I~;!ST_6S$zjpiA_X+qUgjzZpZjH+7|I%XH zW!8BwL?E?sp)u}|bmE&K1}k7PzMV2KTCbFTK15}V4r~{kQv~ohjOjbYnwRhRH8HW? z`_UtsK3Cf1fPdG3JJydI z4oqKzwPRr!=QZq9_{UkWi%mS@K85`i$CI0T209cQ5Hl>mW?erSetOHp7uy@d~wM^4-&Krh@`cCCrS+?>Fx;fs+U0ob#Gr?Fe_zmn~VwZUB^e`jB6D;LzQMDF_DUeOmENq+5QZ$A=<02dmGBa zAaJb6)6I7j3b+cn38lT3#5hJ1V#A?<9d9x2{wqsRI5lHaql3aydMC8cSm_qid+!VB zC!TQd_C!Wk*7YN0*r+~z^=!ZfMd~8Ef^tuKqwP^~Hw9lnQ&bQ>_hzH#u}x89=G@g% z$8mr>zg6-(y^ELbqn*9_twxKCm7U5av_ysdl7N1!e}4;HEDC}8ed#;~0I(1a-(!2o zhhMoM-6ApK+@GT|E#|2DaSu?yX1>NE+|N1pnToJ#6e9stAEU-yBKwjN06@}Qt2~`a z6cRsa%mN3(oaf-N0$dli&lVYwQOv#*k!;Yb{PHEM$#Kq&U{vMb#rZ~kRM{5#{Tg0j zr`+9F>PgQ@H##CAI<8h#i#-^nLp;iw8^n-Pb}+8JDA+k)4UGLCzTPq{s%VWL-3)^a z4bmYk-3myDluAjbfPg679YaZn64D{v-Hmj2mvndM-JbJ5H@@8YH1j<3VP>tp)*HWg z9j~ZkqzRfXmk3%Cvjyj8bM{-yhY6b>R7c#f=txA1P|X>d?Ndy`0Yw+1iz%h)Pp<-` zcF9PCcru?l#QIY|HJEyRtZDA@@twztsZKoaz+eqki{jBzcn`p}7jU};T?5#M=fE`e zDuvf=AfCiZB8P?skO+0V`8#BZM>{QAG`^C1vEQcrCG~KW913_(3VMcY`>2f#H3bBB zNnL+{Z|n$geH$o^EnW|OSecs)yLl??%Y>dh1V>XaT2iJ5^H zkj89mZhAgFT$v2z=Act}o{#!s34`Np+VaqwgPMS(wR@(aYih7vvY`$O=H%4dt0Y|eOD6J7{?D;y)UcsMpH_LSi48bmT^f^MN=w92GStu zS7~XxMQaWJf~2R#-r_=5h|cIO4JKGw3i+>{h)1uPsk^e&{k%~1~hQ{FFkG!^UE`(^_n>)HUokE{p?P!layg$!F=BzqBaLnR3KUwWS1N_$4%g!rlo`=+WOhzD;4^GfwGsjqDrYFoy^r_1+x2~g{aYo z(Ws0ts4TbR?-Yxu_LaSfr2N0aJ9VM>UZ*413i%XMc&b!HBv=>+gF{KV+I;kvu3yCi zwPK5^-%4B0A)4dQS9^kPbslq-wuX#5E}NF#)##!g!?vG`xHw0)X)nt7-CR4atRzJi zBb6p{YS=u+sm#v(B-q=FxSjq4`=TxBYA&3#Z3RH*Go+)@NlMicG->``;H$djlH*Lq zAAMzhRiamP1v7PmmbOR_wtjH*6gELTIy-L?Y79I$RoTc+@$M^}KAKZ&O0_SZ=sU#sFfe>KOkZq?8vTdLh33u)soqW;k$i3iZaW`tCg; z90v+QMFOz7GkPrwvY!|8up>a1Dj)0Ruvh;^DJxmKg#XiU!^9tGpE5l^im==~e3eYv zD}HU(abR;%Y$=Uk{*lrry}$CQp~$sMWYncjkArPJH=KiJ3kIJMVo^lgL9SqSb0ZQJ z;(@^Vt`sqmTV&XK2|(Mw9H5rQtab8^Y?9_|*WHJt&ZdwZN%S>8N}t@9p|B2{H#tI! zYsl5v6i;O>X}((&j8ii~K`E_fDbHdl?i~+r^NS;vrpIwcAsipF@L#*4lzc%IJrF8c zDh^+m{A(!=+tRUsUp?(7JGtX^&bOw{E}He~x*pL+l0y*0x6{?dINsynN#s-V?ElWy zSC{Zt_X_kGE2E^QgitsA!qXzj{3*rOd$AaQ715-_)|&-*D{kJQ+?Zc}F-b{o@^h=d zrZiXDBIZ^hjEut-O?>u?;%52ukIvIHeJ4}U%Xd&i$O_kS=PzV8O%=H7z;#l1t z^Q=71Ta~SYd7k6Sj_(>Vh=rC!K-Gm)KMfB_*r9IwLE|E8?^Et=+LUBiqO7?Q6wU|6 zNch*Y;7~KJ4hEpV_BNfUC`~r3S@4CR);lPwzikdBG|0=p;7K%oJ~{4* zwki~ZQbBijZ`<_DJ!C*3U6BC~6$#L|D*i(~?Nzh(wcM$k?W?^TsSqTHZqFQ{7UMkj z!;5*BjK$fyo~9hDKgKr}a8}g;7*!m$%k~O%BM;Hc3EjiaC{4xuO~AF;Q}LoMU6@B> z6KZMi>N))+9YD!V!bDV@B2)Ae>R12j%gb#FlDr@_wy$X_Ix?r8uyaCJ+vqR0WGueu05BHmF=}w z9v#%bLy9I2qgSkS$FI=ea!|<{ehIE0&eg(istX51ndFOaALBBI%?xP{f>cL^hJ*$X z<+BKTQv(ZB1rW4Fq@h5oi^NUqj`CJX#Ida*Ae!nS7*Z2~Vj~gO!8P$b{W3z%5@s@5 zY*t+8(X#rrOhROBHJ4WdsX6%ZY1b@Yn~8@tQ#B6>$W;ycVPi+_M-(O%zSe;gnx*3F zVBtMg3LzU5ynIXzp>Cvct=@CN{k68LYc=>N|2Vf>vx*mn{wlLXx01!{y8TyuzLxEr z8|0wZskEX7O`j7g9t*Gn~`rDg#*yA>`zt2{SQrQfC-b&Yg zIPa{(_w=}}s_K@rhf>A?*ky?v;Eqa8ti8I^y|#Zyv@!}O!lT#^olqazpRE?ro^sh- zXTt=0<=bn79X#gxQ_YoiTk^@1455;}URDcgtFKOHWsnFeSJySLp;JN&Xkgt`+n@C- zpe(nqMjFfOL%in{H??B@n)sJG##VoC*E2*owYjzW#$BSCZ~0xp4@V8`R@1n{zA5~M zk~^V^{*Bwo!aV?vS1f$!h_2@@thJT z*W2YF_d<{-wxpA^-U9QFg_dF)|9*N+a7QBdP4KKHe+|JB2Koi7!StQ z9U2ufiMuv9Ih3P~B`Qgtv#TwCI2IOmDuwtmS}mtO?RKBYMPw=-qGt{vwE1Bhu|2bP zV_mtx_atEv{dcJQSmFC1TYJ^c+V11T${S`hK!(!k2+OTx=Lc8XUM+7n`mqs0tMF}a zjh;O?>GY67c%B+4I6dOw6fP?g(m>{(7Y!YypZxTN63S?ps&($Uebi#PT(h~yN~a$q z{C6?c*-*B{TH245d#vbgeD+Sd%1-cP{ujjwkYs0le?3h>@tn5e@Kg%6_v8B9??bBv!=vP!7^3#+b*9xf>;xt6y%~m2*lEb(Wj&GY-^pl95~Pdet*Oc zU$_rtoNV^-u{AGmO&4!k_@>pvqOE?>WeD=rGHW#uBvJ15sc@?_LXL>1}I#B;d z*wy`^hnKza8gzYE=LT#`wwo2)j~{;H3=y`F^RDIugn#L1;AO*1Z8^zHFR7e$Daw)q z#CLwg95r2C+%9ev6N?_=@*1t49W@G5O_e$91uHRN=qFPdb7E?^cagMkt& zNGZ85CxNM9(G#w?3KRbD8H-uCyna4X14=gN=?7v*j}Ldt1D#-hX!nU`4$CU`QLlQd zGv(n|5*FG0etV42To3cv_%PXFddRSH>=aZ3Yhiu~M6WzN<^pI86wz}Va?G`4~kD@-@N997kMk$p+?x4EDv(rwwU`$LS0^WD&#p_0?uY~RMRN@UG}zgP!$^7g`1oUf{Q~WF zruzE}Tr)VSWGgZNtux{(bZBDJBT>k^TR-gYVo;V;4GVJ^BEZs*nZRkWe|O}Q3;`!8 z{ct9x^3y0}anL8~`aP+Af8#@WENBIeh2>9{%E&7$R4JG=t*USQ_tGg+Q&&+@QB~cs z=LaX?aK&45$GS|II)sU(f7!AS_N5~amCDd8``meda|S9$600JrG+kB#2ziIFu28kF zkLTqg=rn`9@<3+JY3z?6mmC)QPEz#)3KMw$__PtAT$10l2SPN zRg&S_c(XDr2C+rR&3>?2G)=CYgNbSfcvrTX6TM>VL&F}e zxa+xLe>}ew|M1DX7VGzWE4RCR47w@I`&fQ#zl7MRO&z#ab`S|8iEBLpXl_zoQL#0c z$m@Q6{4R=)TZCQz$lpt3=`qMJ#+~!f&Pw_yn_ZFOdUeYzUs|m>dPJok`|TXPFRorc zX|?qQ^5VfbFPpQcd4!VjZl8hWZ)P0@>eNS5&(O6h-PERY+b5ly8?e7kn`E+@#O~#> z*iF2(e{bD2zh*+KGkY7@Ft}qZTn3Kl*}9tN5)dNMsqx6`Hx#k(%4i}Z63`RD)cC~~ zC88rTKOM%(cRsmKNT(2d;9>2E4FEE?EO$=duwGKunFtUY%{Su;yKQtZKD`pUTU$ag z`1y0domYer&|m5}6E8BM!F#;e(3@+$p%5CKQYwN*=AYS72%mNyJAA`UyHq)|w znWyq8Lz5ct0VImhY5ZVxpA{T(E$63xnoWOq2%|`x5VxbM^ExVfWPLp=7fk7SP7TkW zA9Hba6~5aitJA^!;y+E+6OK~%NsB3_k2K*uQ-gNOXpy29XdfOZ2EYR~vX)KX_Vs0! zCt&1pB9JZJ?}ZyL&vBwF-(?hSkJU80>?xvra22V{eN=$`by>>ZNgvue+}sWz>qde? z-v|gCE!5e8&Odq{7cl_=VX>Zmk-o$MUkX$35AiSi_vQR|+a>3Pb4S#hua4U_o-PM9 zkVE}V*i5PH74PWWzN?Yz+>bI2Yu-(>Zs$RXl4iW+FjK1ZALe~GD?xp0?G|B+VA~4> z^n;D~#V_Y3%USYwxxNdGjva9t0NfALvbVsn`HueW6S&VR9`73X_F4o4TrX!L<*cxh zx$K4(a=!cJ=U=_w#331PZhFZkHtP6QNgDvR$y7?etX0gje>Fj#MF6aas5lSi6G?HS zd99hnB`s0Z91maBIuSZOs}H1qyLq3JtZb4-wPnQ9!+(X5_iz_T_WQ2JSC8$b-Ybj? zuqxR=UMA+UtU5wQo|eP-f#5&ps`2{~fyG4?MkNa4PSSTQ5oJdESG@U;t@a$On<%6P z23xXI`gPRrvwVOVU?W0_VySo)EmD-;Cd=V^RVvQ}<-3OArecSKW@SPz@W>WMRBSsR zjzi5YVZiHJDlu--b_DpxoV&G(mw643KM=TrSxbsaFS~d%i{3KQe&) zTdm*~7gu9blgVI$vGNl#kfE>RWdGnWc=3l=TKIa8hQ>;!U*QA#-m9u<52t zFQZpC^4XGBoxsg|zBf!5`uo$zh1HRgvTkPQSjy4?_C&AtW?k&)E>C~)8Uf$7r@PJD zx$M^KMy2DtMU0zg#9Sh7G#Rg6Oj&96mvEOQwU9oE)Ji7cvWSL3{&PXTmdF{>jUc-| zdhXP$>s;$surW~Ia0WXfR&+oR>@VY{TXNp-5sPZWp2!x%75&e57raiywHiug@+xBm zECR^cfORw&rb9d2vX(8;Y!jLye}J``PR?lK0TSJbGx}q$EU#A`gHrb22TGJF@AdkcWgkW`)x3dB zE(-;IhUXbV11)fipIx(7T2K3-M-7%KOW{%oidv}&!NBC@#GTTe6_6nIpHk-i*$)}o zF}H~ zsg1EqK`e?jBq~s-ob-lH29*#n1F!L6`npTYoBCy9qHAY?-K)W$-F$ajpCzW&Cq6Qe z6BC0R_JPf4V1>xiaaj|23~M)(A8cX=3h~|TM8h-v!|TXkCzAYMlNGyvNrFVKa6a2JLO=U ze1-nej;e}t+eod!CuW0^&Ev8@jAJ90s zkok!Em_rG|QteRey$|S%w^L8c3Tk|)Ic#pXf}&Ei@CYkb*1VP}lGe4Bx&F9fB?`z0 z@9a%a$u4toYnT!=?w+fcSQJ~keYV7shNA+&5suzH=VFOM3o&9Un&8QxzV;N@F&c9n zL5KXOyFemlU_wYhPE0^PJLjWFA_0CPA;%#hAD#25#3aiYpDZ!+52^!&?Ube$VJ3Gp zeo!&+MoLLZA)D3+lZ)z&PE6F+)cmG=P$SGy@}Z-70fYHg4u3dZBlLFZ;XpQ_sb7{BTPKh!h>+44kqd z{>4fb<~Jc5rnqY{Q0;bB0FPOW~{B11$u zi(yT#;hchd&q07y&JczhFXNb)7n2+-TPNZE?d7jAM;of4TK(lRYDEY8*i+*EXWc?x z7E|fC6ps02ex<^OEf1G9*Yv632W3wi#D5GI{TB=qe|g^bcc$%lc`i)neaX=L)zLZc zSv%u-I`gebiC6B};^ND9Jk%_d|K<63eL@KIyShDn@oWT5<#>My?M_+i0R4V2{dnd} zMM(+Ya!J`D)f?;X-U8$7^Po(e2MW-xEfCe&K@lSAk>jN-2JmJ+g$Pa>mPfUpWMpDB zk~LYLYq9CC-Ws(Sqb+GaPVQG33j$l)gi}|4Q$CS#9R3k;Zdjh_v?CPex9uOv{pIw? z94~N`@$T(X*JT^xX5o|Zj~PtS-FY|b3I9n23~ebOsr}io_T9YOn!6@E-0HFXwb$+4 zFuL{-BD|fu)-4Vf%^}+X3IGGI$mNmxg_BMU(#Zi8u|@K`?NkL5e;MG`v)uMDW|l%o zcpb4z=4NqEon8-}&3$%K7E?Hgl9J z=)0hh{>##%d5n5im5&;OMzByDTbVnm^dh#`r``0uz(9pQXYAp!RD&nE0 z28HsTSBp-d{GEr;Y`*$nTtS32=6wW(2wPMy$>6J2U7 zV2y5gLL?wzPxkZ}BIJ5iQMWp1@Z1@oHn5nQ%UOsrGBE)WpQ>uS=!Rt9r-N_H=~2#& zHV<=*$~k9(?3>~^fLNtXf^!Nlj*lv4IO%kWhxvk^w$AzF%hcuam8<`?3V`FkcI=ha zFuXoraYL%9SX;Op9YoaOQn;(OveJGsUzI5)f5;q+QQ%DIifH_=<+boyhVdj@FV--> ztRGw8GT73mwf#4oDl#}duP6>NMVi2c!Vs`2VUZ60Et?DnOfjfbV6~@e^76ZZ3R6sH z+DN9Hn2tI`CR!SAfI455v}3;V)xQP(_TsDYe|w<}(er*_{!k>13yA*a4+r8WZAVdo zDhG$NYf~0F`0Z^=U=>Ol9}g0U6T>N~gFgyIIOqTeWdC~LS3>`%4FVn{$y|yPHl{g( z5&_dM)Ie9Dkk zca1%P-%OUTaMHrZKba$MA03HUF1$$$0lCe8O%n{2OJ5^Z!qiN}#WMf~UbHR^y-!N_ z;{gd1f3o{*6Ad-u#V0vIZczcM$yK2py^mqTf&mpHUf&><=_5wo?SGf#P-G~XZ+4Da z(bT3%=U{(*W==`byj4tywSFjK@EsJJlO&9+yUJod*4U!P29&E6Oa>!B2IZk&6*+#~ zO$mIkUYa~zb8*d1o|bXSuF9&z;v_}~8UMf3@Q^OZSSm{9TYtMo?)3FO^*NO+C!}~e zUg?EA@j00oXDTxA`j%vvtuYC)^2+?%q?a{gbneq7W?G8RQGso4e%2BT3q}TqGP^U& z+`HsDNg%IyKyUe*p0w508#WP<<@tH-jM3NSnY~8!t`|)G<%9b$ebr~J)x{B(CPbnj zA)Zjrohqt#b1;z*8++swO@D1UF-q^v+vnX9>^m$a7aY*VxeG$I*thMtDKv}Pp2oqg zXIYHh0ueILQMu$GdICh>0ZJ&;$k7u^L9gk2d|)g%^X91PcP01~@x4C0w}NU}M*eHP zfJGQYogFQWpr?<1Iq=bnFFq#5_{El<7y2KL=Rr^^m8X}9xI8;+R%4K~(Xaal2Z>e0 zYD8gO3ZQxNa5A-&(&uUrn=sYc<#wgd~Nimfag;2^3~!9 zKvZf-EA62iq>LmS&t89{iQ{+J1?3^PS4YeDayJiG%fHz5FoC0%C(mDOx&Y%_z=F5WB|eEij!-xW)aZ$4yt z$ju2MK;hnTrTXm}iFz7AE+1aC&|x6dIO~HGbjvsJCCpLuF-ZZSq83K7`&^MQOse8@ zXD}#F9!TJ3e)FdGqz(M9u4`eupg8K2+d-9(+hya;W+J$Qu1$~sY+T=1>w|LO-;yC} zMOsz*Z9bsg3F)-q+R*Y?O)dgagH48Sj>L?cjP*yc&W}~P^n3sg8(Ht;IjCqA_x%nS z<|Lfi=WZP`i)^(bWSM;y@rPQ=_f6I~=?LgBaX50}4<^?o>x(->THnd0qnM1b*;_1k z+q?3{g@R+Q841V1aq)M0J)OyDvfKTe=H=F-w&1?nQZu?HTGLnCR07}0v z&cRJ`i-j<|9|lP>URM29e#ps76CMk>@lu3hP6t__c7I`r!f~tT_cJ+SBBKb=5%pLV zeR?P9c#Ee}MR(V&`iIU1a2}%Yg4*nWmaW`j%H!^l$U}^&HJjW0k7n|#pEzlbe4ojvKFzNaf|utu(jHbjt-FgXAVXmfW!HCh47Oz0`UC#^R7_h3Wq(l zL^>e-_kI8x1dzbO@~WsvLIU&=A-V+xFxa=8k{2uh5cwhU6Y?j=s`tcSOLXEJvneS6 zBDH+(TyI-aDxyRfW!BjbWs}E6ue8!qYopJPpmp#02$V@Vz<&#}CByPnZiX2N>g<10UtmUDSQ5&eSwCi%sHc@{LKR>rs zj()FZbt!<(8BI$e;Bqc5FNTjrX>)!Wu`^RA9rppz)s5!(B{3gKYr=lgo_Hj!)mBc+ zmy_T?Mun@BnyjFx{Ltip5Cpsf0p!=}U@@QmJ7_V=%_&SNJEh)Jf7l;0LQ-H^fR5md zF5UIe{=1k`M>#qTO`!&QX)naHX8W?{8C3@-x;PLB{ z(XS2{?X3z_{0PyITOJy7QeOg!J-Bxk`Dl?0TN}*C(JfiA}eD zVt)P(G|jGXsVi$_A_P-7W)0KFJGg(Lj$9BBo|3QV@1il%8t!$jTneEJTvoE<_F8Q* zy8#NlMq8-YP<`)qY;Ma0gnAfN zx~aDH?qz+(LkD-qt=6#ZiB;0h2k9_<9=x@q-2y=?78WhAPjv&z;K#m%auoO78$K*= zF|pDIHaBuy{Pa31wy?~I#uy2t3AV$qIC8#(lbFzNnTpTH$7t(5=8+))?sLcj?+)(J z51D$~y={bxil5f<3yb!gQi^6(qv|=%S}zAG8x53ik!F_TJn1py_m{Wq(_d%$VjSsz3z4fhg|t=C5jg z)mlYEJw3;lmnqz4YHx2v00{{R&>P$soFhu%c})el-=B1sm6ZY5goM1H$OM$L55>RQ zN)I46HA+wLv8B$=&sxqoq2S;lAm}{2PwfG zX0*UtadB}82|u+03=|Zc;UsXB;7Y4^wVhwk<-Lg8kSYXjc-P!iA5fc5r0ilNhHzb1 z?tXa4%{;s#k=j_vb>YQ)N$Atx%J^CEBsd9Adw=)Rf|Ggb5_yrc?>+P^-;@}; zcMC2?)a-vUvDLrm^4O?4%p2^5PcjP z@(S2H4XO50rSCtu3Vqh_$moqVVmYxmLcV*S=@?CzqdIMPkwwZFYR)8ns%>}CaUZ$I^O2(K}=)QM6>1#KoTqj1m( zQl@VQhsd9;UzZh36-|?d{yxP5%0@rxw$H`MKMwZd3sQpf$$o&i3F9H())R)j|IEB)Phhaz0d zB#@D-0*EF-PqOoW+qu=?Y@uWzvflcszpe%Kta*LH zNsNcPBY#K3(SaV1227Gd#szm#3mKsp-Zu;~iB42}>KFie_vfV^CgaIRMKN7TT9!Eb zm%UGq>FS{rgvF&*u%Gku@37Z?>zgjtrN3F@2i{a)s8Z%WW$p|4yw$->WhiJ&(43u| zkB>IqFhyuB&`pCFPYevs@$u(6Bf#VGD_sFVfDj2W@XTTl!uJxN&tG+Bafke5Wy&Q9 zmd3x*QqP@`w6V^D%tg7G>G5$3Sr&#MZfc4=;f`GK#j=Py9^XktcYgRDgxlZ%CyWyo zx2wL}Xdr0-MNt0*DeTqxDnB4&WVAjI|H>+tJMDdzR=xdBnPK;m>mDl*$7{7zYVaqa zG1$SDm@w{P2>)mO!78$&g^A>RgLuV-iyFb+pmPdx710?qkn*_h zS2BvH?fneJv;{cU4OrRuD{QMT^6*!rHJAQ5qXG$9+i$S`4ZZtw+7>c z4Ko-!e-1j*v=^dAc^q=T0Ji3*?xfncER>oG!VSdK94_AEjEHu6+wtps(qV+g7rpot zG#rMe?$e6+0kt#n+|9fz&^nLKV*dN!PFFvD#YFlKo+(AY2(LaVRzS?H2?9ip^)Jnd zm|bL!TrhOw-c3%A7n|1eq5c|YMrh@2FHxHWy2|?FP;>#m)5<6S ztyKp9=Z319FTcC>LKQQT5GmpB!@8D+n&p2BL-foiew?KL61HrskBN{g^tK8g zh&Q{Y>aTH)5h0_fgZ9k<7jcA!H8^3i@UmZ2|gMfwLRFC9jM?L(T1#61|#- z1ocM>XRRFvzmsZ(9V{&KGHsadUidH`5zh6Bn$;4=GY&#=&8bD5$zgxb#*$%ze1~Nr zJMloKnNHH*3G&}X;(=6xR@Crs)PVn3{=)Lm6RH2Re{fEp9Ea&dZnA*Wr&?<&(D;^$ zD*eZg&DiytQi4C64#mY|xRkMo9Ptsv;RyQsz8Qk?=VXP=YHSibEvfvQ7=l2lQsTQQ z^lnhXA^ql1*D}pHJ8vB_bli>U81)OjE7ojaxzY z57z%=ra)febU7j3p5vBF)QmC11oPt zumXz1St|;nT`98?uecpzax#PfQO#z7e&=feM4*@7{{p|T9TVVsKf%`a<2g!LUz(y; z81nf4eHg!yxw+kGR(xRv4G%!~gD`Z%m|`Y?RV8!l>uoLH#79ybUjR63mm`J^F;S>Y!1-!ChfJ^mN%<@3f)OXc7fp*Ckx$K{cc6YRz3fylt z3ittivPBh^*Rxp3$1@9T%}XCPh03em1;&&DaF^ybRwJE1e-mE<-+t;Ov0r!>5A!pUNI=IgcDIk)_+cXR2XSa4?yx!ODMHe*NFx(r#pAWU2GX zs?>X5L?8q8>yf9mIw#)#d~?{rBx{FiCu+j!?*h|+Tn>7FUoufNV|6qP3y77yi`vc} zo40M$NBVE$oWd%d5YGHbi49r=!?)9vdEyX2Lsw-8+0|Bq5?xywX?3CA-d?D>rSkrK z=?~C)Z69G@`SEArk4XeU>bcyZ%v|J?q*;alzH72wL!EDgbk|2%h^4;&nzXxiX zu{yQ0jIe#REC9gGWFy&<$mMJz4hWouw#vYG;;!w~xuBl~GM}dMqI#EGAuxDgCxi&X z@<#?B>d-)jEL5oheTxxIN*lPN&BLpzVOuve-%pOuV|%q*@85w$Q5ea+m%x9zt{VtB zJAgq~*;(3klZ~s>h0C{6kCn6)9t)vI0kuq_7S~y0#%|u+x_K#*=#jR) z)06ho=nG~gqVP7sXTOSvWp}@>VU-b2F}6-W25KpLp3WQhDp5OQy1UyNy~s+k3EIbV zy*~ON2*7nEa;&rDF!KIR60akk`Z3VVCNp*8jAFr{=YIw0snTFZL7r1GfV za>)WKj$&)63(W)Td;XsdNPME7Bwf0=-#VH2A2f(v{!R9Ev>fC?fOEZWYx#7~u4k)1 z?au_jPYqj&K*2)m4ZZNaj6gO=20F0c*rZZ)#BassU?_nN^m7F2BM@N*-HI4~oG!vD zYze7%_3%&9V7!rQc9F4IT%yK;h{80W=p0iOnnm*I3+R{cW15sE!5%3C9;xEi(+l7K zTg(NJBNBp;c8mccUJOxRl;(KvRU{wSzDhG`HH0Du>WcvOnDpvU<{ zP```6Dv0H*>=5G5=c#8lGM~mQwmUY(U9QmfDXFw{t)jN>c$@4e zv^CZ*_bjSIcPJ62amxtVBAb#bq1Git+5vSx=+TSXbe4B2tJo#DE~}e@ z(gzkf_l<3p3>_jGs!AZ6tObX)QZ=sCO0r*WFCIzJW(r#W|6&>nur4B8!22KIB_}wX z2y0_P?hf0V7Ur>RXJxzH{W)x?t9^4^M`&sD-OfaQDOjp>Z<@P? z0m#BM4I3J5e#wNg#8rF0a3w+pTJ@&jQXFh~7GPi&(X;V2yUcoXSsx18DVapL(c-iY z4K{p1Q#?R~h_W<6EHlYJ9rPyfL8*+2oeYFp3lC`K$GI!WDF3mo26fIZPgr`aEEo?7 za?hTM{l8%UgAX>y{cVDYp8vZ4!+7!ILGvVIes(CT7Ui7JEg}YC#$lgy%`;;AiJGU7 zGWHP2U3!;0U4Uh3f-Gt=*l2^_G*oaQ{k#m<;EXLt(Gt(6to6(fd;a2Wry3s2=6P?J zb{j)9DJa)cNPdNt_7Tqibj0`d8Nz>{DID6zMPw|)GhKo2m2r<)z$qNZ(6x@B)&VPe zQ9IuU0~fA}2fva2U@H0|u!v$0y&7|_B=wJ#@=19yj1n_Yt9K<#NsARj$*}MP z+W`Me!O}n}Z{%)l(d4Hqj4&u#?t1Y1rs8yi|3DuLQnZ%IZuM2?nKFN0Ob$0>nKV7j zghSxFBxsxApir)xH#IMH&+D!6jkzO&D15h?obodQ&;h_!Rdc%ttnbiS1&6J)?jEwl zdwZjrM02J$pYX?cCYD83s##%xzM?vLUtwPtW<=*~jqKzg!S8$xkK^F#o*`qM%)-CV z3Ezk`8JWbYQLMZYl65VSXp2Mt-e|S?fjQX66*G30SCP2GsNVLp<#chcCVMM&@nL$^ zYiLoEm=TK~OC}ru+u2qf0egGfu79=s;_qh7EYQPOduM}C@Do`#A7 z9Poi9VM?y{*+pH`oX8%dBnj#t{aIX$^ieiS@e)i1SxWMB8?;LD)c@YK+dM~M{$Wej zFGGvo4ZiO$L;nK-x_nyEe0ph*1$p9~KVi#CEg7xKHR|JG$u_pNl7=;oc93Gw`L-Ex zB%Hf08F3M#OBEfu+ML8pyv~sN5P5L!M<9`>QjHdoeC;d|nJNyVUPcn0#3xr)JI1DB zwhGz9OIe6d)ikU72Z>%U2!cO2WZ52m{x%%7tN)epM*&882kBc#dS09*vZnjJZk13IB93EK% zB==8n#pS-Y|06qTO>iN^U3dvJ^!ODE4x1I^+w%+kDQD^CVClAH>9;}e2LHJ=S%0ud zIeI@AS+_0OpHh}?P8OQSK#f>qO#mC}4TEgDcyE=#ky5%fu${@z1PMyP)q#3%adxe` zcoUYkq6v2Sh(bSEnh;L1Qe7P5WJvW-g+<9Z1>=ueJ-b4^QJ%#Rty zqZm!ZM7ON8<=V^pU%woT>A)7UjL$>TcZaLQ=UHFNJW06CcGOse9yD<}1jk%FOukiN zh|aX!UZ0;4seBS?AzH|*e;Js^aP@<|_|voOr)W04fFRi^Bpywpk!wT`GWWN9{8c{s9~Mu{3l%2Zdv*6Ov#AjtB=qslDYEuQOhMUgF0G zL&j2D02|#@ZF6RU8D)q)cj^hD)u?ZP>5;!+eI*dHz?DI(QJq%r>5(&4IUE6CD)I1~ za&l-4MFO9ad-@|T02pH4K+?~{003B*pjby54eCo=B32#2XAmnC2xXFA$l=Aj$lXwq z&{kG7Mx0=cLspjJVU9Jhd+%jkEBO}dKPM_WQPk-%C&H73qDtSgo7B!%i5zb?0f0i@ z)6*xbg%CmgB%v@mC~iB@1!;#FKEp;Mq6x*Je8#EKs+P~t{oXiDr7T=t#xmj!3V2l!0PMjt1F8V$t_OAt)strG_JgB0)ACK2}M#=JGNmCqW@F1m%M#D|rma ze{i9q?9J={aRL567?H8DF(xKvqv$DGFdk|r*iMB}{R4_dEig!CP9i)}(|>=yNSI(R z{y8rFzL@Shpp^0}^YlZ^!^3Q!ICQ9ngb+ z0D5ZYs^yd^tnA$JqFoTUzTmaqf<@-maTiw&aXx< zKNaeG==o%?Zds_Sr4+C{k4!AtTmNf8SMy^b;~A1HOaXWk#Q6HJ?3{n`!CjpE(X%KV zK$Lpp^X+}J+f%$<@6yr|ry~*X2p8Dv{j-4l7nrztTCo;L;r{OqW>a?E|7pPD41xf# zY0!hyHqYj^@1>!;#RNPL~g~U zB*KZcv;J8frvKpcBZIkTUA*bi8y(0Px83N>PLh3l>msHn4@E%pfpcym`Ea&DaG*XY zZE^Z6p14mzBEg&})E#}OBeXU)HnX#{Ad*BX?0%j3E{dcN4OGd`S6kph4Nlj4Go-@$ zdV7N+B9P(#yz#ntsz~aZ2Ij*NumN0eATGc8hRx-M`=hy1f?oZ3KwoN*rvN-+MFKaa?T8Cy_xE8{e^WuyuKGJDN|2*XHVX% z@^h~LNRrFWVDcgl4|$3c-o#zIE@_D;Hp`pL;yXQkdlr&9Te*r;5__3+@-oNs!E^HH zZfITQbL1PO&Pz|D%U3i)rq3wzLaY)+qYCzU@G%>3u2&J6g*EDLoV~^VE_<|xln9UZ z))lMN-k&E#h-gXd5{va8+XETTR^(9!%{Yclyj$t+c0I`xMq=de~bS8fz{~Vk8U?$8NSq+C45EqRU6aCEhv`b>P zN#rGk%H~-Zl3MA3MMuBrycrqkhJ@y$0ckbI!G?x%5^xYWw-TZKYgo5Jx<2=b9&Gvy zmLXV^fn0)>{ryI8SZkBpmFLBzIypJ{MF27ScUJA{#`CccK&ku9Y5Xgbx!Kvyj*j*9 zbr8f{DeERTd#wKQl*qNsprRJ{8uXCkX%huusT-Vw92H{Cw4D^IJcJlKm1SO(tjFD2m$!UK+mD8Fm!P7Qr1rCrMWyQ^8Trs6RpN=kN+j-QJF zKe+n3PxvB>FF=Xnv4YF+Y4Smc`ZN2w#WX}FS;SS?Ju~Wfd6?cLGXW8ykL{D@N7%|r z)$YxTbKbYD1m)o@)dzQR0Rx$koHq-g(eMgNyU#mwXB#>`e}H(lfC4bTxmp21Ab{wu z=j&CzPt^1WB(blb`9TsQ19%^Zj_yVz{>zA?r)bR<@15M$J>T>lU3yCKY*@N@%;iY? zjfh1ICN50HK9m%A zKJNa|N=FfIqp)he)^%KnMyl}bcl0>BAZ33CQWdmv(M1*Y=9(_&pS0Zyi6|>4E&o2I z%j3bf>*%3|A$`73eKJgydqQjtexTe9g!6md8`hBr@}-5DQWD1xO-)%Pxd$?9mUN{UZTUcCCPhY4JaGTMt8 zdI5S;j+Jo0#*+MFtdQ61{!06V$8TsxcSX2KzOGdo-SZli1JFpsi>spmLtocu1R0IY5WrD?7>SAW$B9gMGB$E}K{!Eb2u^Z( zpRAW@2Q&^a!|I00x7v>El-~guXY=#9JZM71st73g?*SMwY32y+&91tOr?|uaaD&e% z&Yah*#C_f62Ag;akKLd9KkNrQUq#Qhji;iz)HJ_$HO`zGP=SLLBt60VZ82|QAkyI9 zB&nmQNS_Ik>F7%HL-M-1;oyhs?nkk!S?me9kuiK!!~piE7nGyAjeSofpEQYDY%dg8 zG;!733`Ls24d1qbK`N%(Rt@B?rvP(+eZO1{Ks(0@W*E=rd;1SE{xH+Pe9UjrD&Btb z{gMlfX6lYKzN6jpdKdTlt@)2P{iAHQ<1QT%Ube~_3JA_;h*nk(kjIk{&+St+?`3hw zQQmyvd8f^^0f4 z;lDSmI=0Vy9IPKPar)i{1(6^CA>d*@Q=Y2-13;@SINRLZgmGG6h=>*}A%=*qU~N+c@HGdw-@J;$nn%Qztt0 zUyPTrMihK&OJ0I~wH|Oe0(iSM3g$%+|M{Kp@18AX1qEA8oE%TBPy}rHEG6>Vr&{v19qWM+u}xb&7#g&wW?4SL1S&d-k*AYgR$3z=D2^)f^-q6> zq*2m|4#5Dh)6=oE{F>zRcAaEhos1LGCc(g|=zDTYRfPOM{*JR-qt|?K&w7-L+EpXUof2pfPrD0 ztMh~9WOyJU{4v%^sxss|9C)gTKJUWmD>Bf3m8*R#AH*|3Lga>?*U5n1qdxMOrhy)8W=aXw)m}#&;K$%MHldpm{!~e$lqS?iT{3}&0 zA$3Rp3+3xQTwN$*4C=Em_(1R7{_xRwtn}Z?Y#g91n|E4$wz#n zX5w~?LKsSzcjdyV5^e5atgK0_bKxEa3+dRgWXpBEaz=2^7ewIFxp$PZYqx=!J?!JY zktCs!NuV&O|$!Ek)1=oKn}1SE)x4vvKfvR+1I-AJMH z+#+EBrssElj6%p|W+u=$t2%Y!UGYxNdAq9w;fYgAMl;25PQ;xfWsM>a6-!)>Odbx8 zpu~9)FrbXfsl4CvEsO84Y#(6MMbJlOLF6R!rbL<>dWE(88q@-3i*D~c>K5bh7J9py zD4E{EQ+cZC8U56I8k>S9*9PS?Ag_sWn+CZKPt5a;bcu9kS$qPa=RF<7rX?!#4=TXv zs?BQ@$Nl*GBBVth?hE|K-`w=337Jswe0#CeJiuOJ1(#6m>>Q@;8_|gNChVd;5-5oT zQrf`2WkfXY5DD-K@>77!|A5Lay)0!+)GI_HE>* zbV7#DU_mbtdM`BQzy0svkv`&4o$+}#J4(>Q0g;*aO?7D+kkQo)`$>3moUO~zL2x() zF7S0(M}Kp&vLFIE^Iw3zTN1*$l{d%N zy%wnr-OQ)Rw-`Phsl!;HK?>s>(%stAqlxnGp-3RGvwPh+70qW*!pi3C;(PJs8c3E_ zx?>;QmyXwyA~=v~0aA#VZsO&)jPY?Lm-8EPDP@6k+oN|H3cdjNx1Z;a%L`8=Ajuu= znB`L_C19RXW)wtAkEgfo`ktvN(^myr+BylX^IY5fKwwYaW#yrvr2ei*n&u6`Aw3OE zM_CyYk)~Zl6jNDl9$ZuhO#~}@Brz>Wr6r!?GHZlt<3Y(>vEiC9wYwC`Tc&6 z%ItP1fK<>=Cw!Apyl#*v7GmSPRkw%M0$Z>>KNAbZ$npQ= z>3E;5jmg?SPW_#2)7__{o8?(vXIf-`>KYi!u?sofZJ#}XvJUXyNIW0bj@*?P^S#};{Qv2XA(#)lp<@`%4y z?3c0pQI0w#(rMMdqN`bA4qEzG^AVS9nP}#x(nV>7E}ic(zk85NBkSrL+8TSUs)XC1 zaDF?=;Fgg_OOx3*Aw6x+_n2qhCH7wpi);qo@zJLPFwX%Hvr;lmwX^Y9weL*mx|+16 zg1#Ff1nc+n34ag8D8^jRC!FiVKCXa=tQ(f!MigP?t|hhj41koma!|^O<5y$+FdLLj z#-)Va&SJfrx_JSk_MBOCgHtq@`mc|qd98T@u8u&%=9~v6oG>pAWbSkia0PB zygL$bK3#l#xjj(z0LvRDXj>IGA54IS0F{-MovpTsWRDB1`^{`>j{G4OsLtCUi_P$) zeAYX3hQwT#9efJEE`9yFK%5uPZFRM~jCp?`ynb6|+x#y%f%3?|*Alsz3#EERV!j$g zPQ#Vkj|*Fll;0+%!zHNsE+*NUOp*zxOT6RG*XkG7PoZZu)LLVa4PCE|<#M?tAUUk% zCetJ0H>(^Kd#|2r;p@eJ*Ij*+lYL3rtVFLitgg=D8L(CB16PjMIs+cILZ)EKHNtW! z3WJByj_tdfG{MuzAAi46rl_0Fh&WW$IW1M-e--m_-|6&r{hc` z>AkHoaYhZD3Xq3>0e&IM@!R2h2;ckfeZA@q&!rzv6F%OzG3&a8TOnM{8*9*gVEVQA zitVu^WO23A)z-0IJow(@b;1$dd7=JeJaP$BtuOn@aI)@5-TRQ}=wD6;8XL zHpaI#3}T?5L5+X)?$bR+Lou#uGu=Y-UZojOIw7F$CdpC@`w6~qr@Ak5lq_FS@)C6u#2((!`Cq+I9aS? zeDh{gI$rwyqF$|?^YxFas#Bpl%Qb-msTtnLqLiy==|G^w24`p^Ve-GvJ)X1oy{4Wm zC*G+vDIcTfy>wSFC___O-UUg%Me2**HjDf4G@EbR;Ava4-o;u=);T zIll8w5%*?bdav6m2mLmeyS7E%;4QqVEL|i9{+S_5USIX$A5OIyUW{JHGy|8vVcEXy z8aG^LA<5IhqZAW4up?5cp=#m!fVQ$-4aP@+9%P z$qI&-J2MCxh(2#$p^Kr&S>%OC0^`@pvPn3B!VT3Hsp82I_^B8%-K2s&!*>&Tfo@;; zzj$nU7*%{+o~^DuZ;2ay@dzUajT^tCzhbTQBua1nsJ}uRqMTZd|mWk zKPRtS`p3Ya^+tQh8PUbH;Oh=Ik!lcr1PGB7Ks$z_MZh0Sg6>!F-$Ul#>oED}dhSN; zzRA!3=Geg_NVlW2O7!}4-54NXvQ{l47pL|fwLDD{%x61S@36YG#8kW-iixKA_SbMh z=TkJ?e@_b&LDck=9;DzY@+ZK`(U}7p+j7rTn#R#mp6>1@<-)N_N+d+zpq*Ac>f?*D zMJ-vR2-Np5Tt&@AWCNb`+I;UoWOKdMV{_G{K2Lx~a-FCL{`U0$T5ezNZt2dB6|*Tk^JgxhZ% z?3dlsB<{&A;51WAXe6g*Aq^EHUZ#KB;F#oIu(5su+s(t0J8bX zqM>3i9VeC|Dy(Q}Z}ou`)wnSyLps7ZY)|)u6bifYe1tME4Z%vE0+Eu6Qc6N5_IY0X zZ8FR=w9+;*lvw{+*e-G&t?vXBOC;ACCNa>yH6Zp%${euG6n*(r!g_+}B;UO1kb0bj zrYuYWBhcIL49+GqHgQztri*fwpKX&zpIcvF1{R-|@;crfRsX4Kv?Zp1Ubbpii?a;p z{+4|}4iAAn87!upXn*xI6F&mQKn3^Fa@WoO^iVL-W4CB^e4nd zv3o*h0JHND+E0;k;gm+Vf`QOc%X`8HA3XELCEg-P@}*MiHzpac^~FXH41*L+9pJUW zt1ywcSRI1=iS@`jA;_CO5U_Wi!2o#)ba+2+2N*pRm1$IWpp^N=c4mM8EujziwtrHEFEQ?l2MhBsQ;klvVfrNG{NciTQ4^qPDZcncC zX%iEyuekwVXU=&ryvo;QkjqVIYwp+X9IeC*a$v61j zQkt>J1Anrd?OO*xU=h=g06$~>vA;zoV4KT92o@``D6KXMp143F*bUhCu4-)l3aok7glEMWZ?U8Yx)zs$~X|Gh(7DG|Z0 zXXg^kEe~;F8s9{Ap9ZhIaz~Ax$G0akCISMyF@3p=Hdi^T*J&jzi5$?{K3~ljW(bdb zrm>1od>H}<=9UmROfPp`_AV@>Eumg=Nzw0AOHdoqVVAc5ih?Vkp#XynXINizHW^Z5 zmGCJ5WZDD-!88OV$v??qujD=8-k$skOSda(C&AN;<4!+fz~gOaH*ea6iY$?$y2h1$)zcX*sG!S>&< zJ-6X+^C1`j49oLWKBOjz$jS;TGU<9BF5dN_!sAp-W0x4Zac9WOpm@F5de$QG09FkNlnt}1k8rqO}| zu5>xnm!|hFiJ#^gLHbVFzt9_U2&UcpqF=YJ4H44B-qyPKpfBi)a^D4pJzg1LSCE^c zcfQ8jG^L(@;7AJB#`@F(T;aiKNwEX{FiRpbDKv2KemDRVSTel9Tp?5V^N)$gR#Ld53yS?~0Uph7 zk2C(r%z5#~<~BTykB+W1*y`HZoxqZ9Rpz0ZU*o>=`aRO<)N4m> ze?x-{=prvff7g6gD}@kN#F><3Z6rc7;GloO!7!ynV8fl&#njVoyNDl? z64+RNnv$WlvLE6Ebo~aFb4k8wXfc&$VdlnubL?573}3|?mk*YB+Q<=ZwYvYqj9<#} z$#)W6u;Q=DoW(_SZ=3vAu(Q`9BR<2#>$N01cGdc84rA`gJe}Y~^{>NOaU)~Ijibl2 zmDD6Sb+TmI*3Z#DQVH+C0$TnV5B;fKj!T()$UpDBwy#r{%>Ax!E|>!-uR-H!MVaAZ z_ok(TSKpbZJ3M#qO*rmMBwS2oFoBz|x0y|Lq@T*7YmW=t&R)xV73#ufmtO9~dWrZb zum7qTRX968gyX`mjZ?lHJ~z!aCVEaxP^&+f_dL=1cladRB1!O_v%293q?=&U{TmKYy?##Hw9qP$gsSv};#yPiuA)v` zJ6N7zpp1nCac^AgZoD;;g}2rLbu>tI^jSm*IjVRP?ljU zELfu@_d!1X%;{dcO1c7(>>1{T($C1@w{Ubk#YSaya^`h5c9$qR9}_wCcPf-a z{ATG$UqGC@M8!|?E=EusZn?n1%&^y=Jo6BVR_7Apq(Yl|C z|Kd^m-M3)nQ}`&3ZB3og!I0f0OT%qd3X?W-d->@?Gl#D@<~zddu3WKAMpD$5St~Ca?xk_+lfw0!P|&~LZqx}t#9w0X zs~sSA!5ZUqaD?+YlRaC;`@Iyt zvYmN-HOxF(Gg7hgZ$BjH6*>;5jjMvP=(QcDqplY8LFkj$Gaz>vBj^4*kAaE(jgIRO z>y@+-{cm2{F&;m0zd9jMJRi;?mvqfs92uN9zwWW$%CIcpC3p%APyAK@l;8qEG0pQK z>{o9QctQPAKL{ly$xyJ0yG;+UbUdFJW{vrux_2{ODuTJbtRx+KsL3OF1)a!e%qM;o zRK$aK?n+e}Dl(l8!BNfltUhz*K}Py!MK9ZCIqfA}wdUg2XZvKCA;FYCBzo}4q2b1N zpI-W7$+1bfiz+ms;?FJZGcjC2H!$dPvz+0TCc*YrNL-Evezf{v?abzS#PCi(JD{FB{%? zAgTNC5TKcXrtwQO%+6>dnS98GPmL9Btb{6DH|-fu5dk`@J{d zXgNme3S|t8tvL+Xr)+Xlcl)5z9^n9sFc8i!Q&MI*&yf=R!BSvP1~{Rhj_F6H(jXZH z6CsRY9hj2YnoeY`nI2Xax{HhHNUWZho!yv_H+4C#?l5qbd!#zK4g~Ey)v$d{k&993 z!JzJL-V7!Hd5F5H+|qE+c9n-y0uu?wO42fov>028Xd~kYg3gl4@7SLY-AcePaUH+y zTxI3NcB+Ys&+U@9 z-DpW4b4GD_`mi+{xo$Pr;r`Nu?a4}IX{tgdzL_sSxB3g5cJTImjkS3;q12a+{BovW z|31LO)t(%9(3+zJi+J}nM62J-U|VKzTTOJ8M|2fPP1+d!otWvZ4IMx-8=0a29ZbsD zhH=p{E-Q31%cBSaPF7nfpsGc5)aN;^gvTTT`89M*3a+b?)yRDd+dN##Q=9mu9oHZ&eOm zP1o1T4${!blcb%Avdjp;THnyn`S1zKDrY2x(3#jBTm)2owr)+nu5h^+-ut|Pu+8N9 zyILu&MyP_U8}X8IaRJ@b{WVIzw@%qYw7o*2rEQHJK3{tK8N=I%4?mw|a2K$rxye(06Ix(qddW`EE$@;}>yQ8*kd`=E~>$2Ovz$J{3NG2WByIhKjQIv?dB_#aN z+T|w?*8r=FNgx04Q{aDjTGy-Fhjc19I_<*Np^Myk59K4#1^gsP2`L}tfaHZ9im$i` zUueLY8yFc_{gQAQmWYosPu-GPrnhxA1pTiUQcr1|iLN>mf`8%^p97oo8W!0d9@0`` zY%lht(=h(kE}r4+uVHu!)=~4hezrtZ?oo2O{w1?B`NS6EY#9ly!$M$U$qmSPx}8^h zzGYeYs8%z_)4WfbGdSyfRGSG28`|KJbmkGuTW{vlc={x8*&20~{6&vWN+C_h~ ze`lwI_BY)nZj1V;SPzu<8%;tE(G^z>9ya|qN8lVTHx?~(1bA%lRT+Uz<}hR<8Gy5& zMjRL_kcC9o4{aOCeHCJjN^Ihe0}e#XESo#l0hZYHn~Fbl;jE79Guj+i{dxWN0?C&? zY~xgiTqzm!XYnoHQ_n)?6g;3@j&rFdF|D>*=F#M5-Y1*njO4mM?exfl;>gBqx8m8t;lka2dM6d^MvfJ7c@DM47>iY8SD3vDiDhZWO$yc@ zYCcKbcXrQHlUyB&kwvr6lhfpBP{+GJ88eP|^8%(A zK{R#wi#-kPAy{;8{4UIEPuza|=qDz_mH5iH@_gFY(%&9~LiYwy>GOQwhpISqY%ayO ztE2U#>FV61>7$~R#T0#=y%-o|W_SsVnE+b+Ayfg&D`bMT4H>F(2+MpGWTQc-HMDa_mQEm zOtR@&gzX1%>d_2gj=c=B&frCNAERuq60R2zANhdkUFD%fh>4Lz7PT7lC$eh?pK}QG znfY$$(9w{(5Y~ZwJM1JDXz+cVnL3pwiRmyAyX)3jr__eH26XT+6%QD>3$OCE&YZ@d zJ$+l7SD6m|NW{Fq`n1^W_%h!i)~vSLz0@1fX8W>`E>?o|lY0JmZJfv0$FYxOqC;1p zdc02C!#88y#fUPz!(sh-d5rS@XnQ+;b*4@#O|+T$mVgkXKEX__t~aT{CmoR$vvF1k znQ5|0J|ZrW_ETC!j=XX`Pd52YD<1Vlb*5X56R98V9TM0Xrw1)%d@SfNxcKZ<{6Um; zdCcPhZjaWdg6Lff)>{Tubp&QoCGJzT!J`%D!g%64MaV!5&sqCgk}pJ>WV@owK(AmYN-6z=RGyP zd44|keD1sP`W*G}uzJX2Vz9%oP{G#!_X{hlp`gXHcn%jAkOuiAA=)TM! zEm)EDTT*li@>T&4m!v2)S``b`JLXi;gG$hpeT`PoOjcG>dZwQo@-i}>SBuZZ zogb@zOMU(SW7(ese9kDb$q2K_KuW~GLe1u}-Lr36_l_g(aJ;MBij`x9V+wws7xNKl z*r{OJNJ{aGsw<4rK-y*1BqjOZtABQ8IZ3@P3HNKBMcO@oC;QtdWr6_z_ciO^lL<$N za({*Y3R-^*1OP!ZUl;Re$py9kD|pbAApqnApro6Uod`b(jQbt0AN*C2zM4CI!^a$1 z84}n>(u9W@w(#oD-a6~)8FRU$+Qu=1jf$u0lRmncAXvYC=j)=0F`p<(r6J2tn^u#893kQfV`C9w*;5bul{2mI5!z`Oi_Y7z=u}z>--Okw?5nC%?kdVF^wT~Xb!iw0B z_2tXYwR6JI_t#SIN%*LT<6MX|Qv~k%MAjd!4B;^dqh_>tVV;{xN`0SlUXV%rLdJ~i z2US2lk{ENX%z-EwvtPY&oxt#9aDwh-duJq@KQLN?RQe71%WXe?lb?2X2~$#hsM{19 zFE)*#q3`M5Q&q^r@nk5f5+3wR>isSMNy`Kgj%l1aY$EllN6~j~Dnz}5qFOuUfitGV z_J;*)24BE_&uz3n#q)Al6lI~bGm;%K7|5P=Z#%cd&eQp?& zl0cpqaitBSStkaDsAQ4fE@=RgG2N`^he6b8@bld$vZe@I-ivS~!O<$5U+`!+v)z!L zDNDk+s9%H(VO)6JKtEZy$Q`B1vqu5K%xS(6tRD54qJyL^7m#Ka-ydFWf!Ec&C;u(Y z-)}~fJCv^|OgB(s+75dr)-w~bGG-ljDu|ux(f-;nC!x^L^E6mm-&QGL5!4fSvwWy2 z`hZgmC6v?DE)e}+q=O{0bl{UzBJ!}dM0)~F5-gJC*SLbN_1ivd99*s>@5R?DX|R@b z@&=jU#5JO6WjBsw3_M<6k6=iy5`Ikb1<#BvGuvAUCHNB1ri_cQiH{B~mb{J^T_|m1 zl{Es3$mc`P1CKT%_W8#E7y2)I>VCefDQu% zms`+$|9v#GcKX=Q7&;pq8oI|0ge^n-$Lr`_kqYbBrHM=l2_e4YtK(<-+t$lJSfBEl zvj0Qz25~fB#ySTTEO5)dGS!wc1!dq7hQSUJ6Tx@15d=vl9b7Ojm#xv7%jv$i4U<^k z$Mk=JD#Uv10IWqxPbspUyh*MEVuJMoUoc{LzR)0*Na5-IG(wYyGmQakq#sPlM$Ze~ z%U{kh94u&I^?Nw=DTYuTSD$hXvJa3-LsSQfmTyY3_aTjLt529*QgJNjuU+UO z`k@6UDO}ekheUzDv!tAH^ZRmOxGYn29r&s40~5h+ps{Eb6>gyOIGPJYuND$hG)mL> zPf~$FhOX`-q}aUGT#HdndWMG236l)D4g0@0`6{OW`jl#Gd+BUa#*S+D)bMrJB~(ymW$)l6(cud{3Kb zN8(WhvvljrU;Sz#g!v`C_FtQQ_qrAhrqw_Q@&ldg1}|BN-TniwY&qqQ!2@j$H4@_Q zCcesauAKWX@>tmSQ*qQw>aP38nph7)Ae-w`wys#dsFPnAWHDN}@*QLPM^_GAJ;oNZ z+XNJFOtDd08*R7hbP*6uS{o6R%<=M;V~|eg?H8A-y>+*9YfB`_x~klC4bv*MH2Y&9NSz3Nx>W+0akN)?UU8@WoBqd6Eq; zDILGL^>yFP72?cyCO0QW7oH@)^`{3aZxRg!!kpM z0O>yLQg#c@MA8A{Y4Vdo6G*S-QT%wZ^h!OULvA8UJ-pdA!VwX+8wlg-5m5Y2nAZTa z6oU4~d42cTp*}pVFL7e{rR2DKzu-0oO~0Vo+!o7zmOAT0?u~-0J_i7_R>Nd2BBG*x zn}0%8ez2zV+GxRIU(%^GdX~&nG#Cw97wxw9JH{FnJ$Iu|HSIMc9?O$+9P@i6N@N1L z_L)x?CTn9|j>p$+ADce^6Izwva>ljF{9`q&+AdQ-T$uSu(cM+MzhaUd?E7<-C(8h!$`YMlY!mF8IwP@0B(3 zoBsoYzmspOkI4V&cGjrJ;$0cIcQCwrz1cs5Kr&J#ynZUAj2o&^`<*AFi}j(04z6@s z@1;OTUyey8^ZKv`{Jm`+iYV=={J)v2EXR2}s*yYv-7Ws}#kcS86e^VWOIkf1^31U} zwM!F%ylzgkS$57a%G2J5VTW}*eVfGWH90<5x!GMl$GrcT`KUi}wACG-EdJcIHx}Qa zKk>cusp8&B0&3T%OT9{!TH`m=akj�XLCuJ^!Kq_BG(0@6up+6cAH3 zw}%L7i?99F_B!?I$FiiR0hVI1izlQfj?7W$w}#f^sKK_@{?%nBu&>L<5>OuB^&Ee$ zt`l6q?@Sz@X(jh;P~(|EgW<~7f^Gm+b`zKH{G1GjgIMcDKM~Z%alK7!06ouR#i+p@ z6Rd^}(D+6BuRva?7fD0=f7oaFab$FS2%=<$oT$zSCTF%c(GAPYoorgv{biJ@%c(dd$Tu$u9m0@m=*7cle}hr1A! zxrNa2+b+IK0ojWfebdgR&S^Qno$sgT^F3Ztg#N#HN^xyXW8a={54%nWQ=IzUd`?z% z9V3u{^(#hScO>wENXeLAb56imNO;88f{?Hg4 zO6SpH+gG-n8Tx5tD`$sV!tZ$|7gi(Q&{QvPpSOG2$Ly_MUx(w1>-~a6nAEK8Wb|lY zwpGW~6;OVQO+j>2)yH)`X3?-Gx%TlvrQEqBG=c6q-fj&-bal3^4foS2E2wfrJfBZB z_!ad89StNWn!;EA^&|392)P(_O}YAuIh}%+&bq{*o1adf*Zp7i5Xgo3^4OZd?PpP%pdQ;X|ti6*RpChtO%( zW!8rm26%s@VoUBZ?#%G6f~E!MLpHLCGxqLF%FHsx+}Whf__JLx=QKKnfEb?fYeLJO zE(Eo-dEq#R@nQ>yv41y`nR}DGg zfAd#)fw!KjAKFcw<(hjb5P?_aWd6Vo$a!C`mgW-Mt$Uq|S-IJ5{)M8)x!{-SFr}9= z;qr0)#2VJi`)yjWXlo7SK=v25I^3*y{=j0*pVZ~|dF%JVv+-k|3_rmmEde-%qXH$kac0cFAhXA~1ap6X@tQ_}$CLD&THYx++qA-yrvWZuh`^Balb*H$0 z2+!uoXSJ+S5@&C*h$T+FiVEn;rfIZJolf^lg%l%n>kH`V!3XfLD8p7e*pxbW&{fQK^9#O+1 zou*V-5_?srMgyvC!cXCgyFLTo)9@L<`0I$c+hibB{m;)u&L2&wO%X))h4=ZVvop?` zBH^Xa_+qVP=J?Fp`(I)ZodxZ)Tsg-{7%jh((xmOPe~SOVxd2)|^wWrxL??NY?*wPu z+KkXQ3^|xY6H>zf3h-!hX&<@;0uza4{(A9Dv-9>FnXs%*UQ^O}=mZ5V%RLRi_OM1( ztBaHds<>7I=(NT3+tl4fJR+dmZSKL4s~RXH%d3m-HIChAfeu>h?eL(mhhlF)cg4I5 z*F#jc{=*M@H(eDJdy=0v8C0iRVDS14jz$FbMgY0XdcGre*t&`KwsaBt5C4D1h&Yt5 zPNfH*Xk8CA!W(so9yO;DQWye5II&Mq7=SgJ3o}pmr}I*yet%%{?MxS zG$czrX5(1(pjO|9Ey0vZBq>sgPDB?iDpNywZ~z8vp1K z#^SMBb`<1^fFs~;PtIA)fe_Y6Dk`V1NFk&kEfH_SxwY-_Z ztN#VHon%qrsk7r~hW&+#bwOrc=3lTIziNlc@lIk>3-D0+S{cDL9Z#Zm6DI{zVa1%XrhSfAtyWLc=1j#H-7x^iY=MMi(;NZ z!>#QRhKsc3zucHT1T?59UsV~Ywg|;IbE^f@e4qgrtT0VNL(^fN@pIL9RlwhD7z=?L z*-%nO5;Uxq_XW16b$<76MU!A4121$RHaC}%WMQ6DOkUj&#ow*F+_Jqst*#Wl_lhJ1 zEcW^x*K%J@hfl+~i)Sn{%Jx}^N^GOch$FMMh2Xe7=UaQrTmzCfq$BVAn2)i#vqiU- z2IN!^G-jTRHhe1#p5hdln>Q)A|zCK~N`$sGa zfxP8RzVb_*+)2}48;zJ<&SwFxL$&MiB;uepmb}lC%&e4g8*6GVL}$Z78}z_9&O9O8 z*SKbG(HIaYALimNXxYT3&^lN9K@d>~vQbOoio-s1V9$vVsoJU3fT*q5IJ4KpiawSF~ zSJArEFMfC3L&->lBZ-VWKjMAAOotH#%eTAB`I(NJoX0#&8oa!y&Il>){8c0NG+=lu zyT*HV+v$u5zfqkAzIOB6$EV8Rg}I3#nNx}E%>`ZT^LWNg*y}RlfTO86PKoXpG-k_DUj*OAEI5dmUO4`o=rDl6`K zr$ec;>~mz0m&v&a;`7n^RyI7y%-ekHHd?>oG^|katVCSevp5pxsLciGKVd7l{5w1S zMdO&Ar-tq4N>&aF6}Md->dw z6YL|}_H+#nz_CbfV&30n1BRGK_Rzabo(|>ET@+DbosDjx0^S_yd?v=>Bt6Mjs5Up` zRl=WhKdC22$g)fA_3G9;s>( zqhD9_*ciqGHl9&=?!t^8KP@|9{hVzKwC_2Z4Ud(-f7GIB)&0{di$Q zIsV!zOF?cxIEyfgOD}3Ew{`-;$633yN@n^ z(Aywhs;q_oi>|K>it>%4eU~l;q@=r1x@$pNx}_26l+I;E5Ckdd?rsoi7C`|?k?scR z?q&Dx|Hj;zJ9FRJ54&G>=6&X=-#Nc?j*u=y@G%K9PIG-ea)fPG#F^ARt843`F6q7{ z&gbr{o|aM7unuf>`9*iu?fIbJr=)6CziG{EagWqPE-YoV_ zAm`_6*HtWFtv1tVGYqZJiJjE!P2G-FpmFR1zg$^7XX{T66JjvBU@#&i=vqNRu?-Df zSmPCh1)R8asu(VT=fm;OGQ5`#yKG;NhB18cNK@Pcs$Q@ift`G&9Z@J`CierSy26*n zi`Wn%wIm zYqrd?&1R{Xl9%8C2YOs-(egUH>)Y^wusa>H;QB|9AmXA|ivC-@QcKrLm+K}SuR1Y3 zOfqE0Ic5nXs99-NHfUMchbF~tyTfX99=18jPKRI=Womfy&@s^E?>t~~mx3=%&GwY? zD(yu(Bqr|FDg@<2G~w%v?bYo6ZlmeBXh5$Xl1%QiG<}v>VUW+$=K~^-SrMDEokClY zVO2t*cab+i;fACCcHhHE?~Y^!tmb2DOtO5{RYMC$ z$)X&oP#*;WF&6K!>Wr3U$Zng(6vqpC4OFqQk)6Zb^UE1c?1jM}4RD3zFGrmu1sw@8 zsaKlYJbaK_l3o9uCkHbeirN+0|C@w6P$ZwE%;)b1V&AK>X8_TP$h`JuZ+oaPo4#kzb6lN5$+nUU2j@+zfLVIcb7+<-|mS3E+@vU67u-qki;y=;Af0~)e2R(}o zY2eTEO)Gt(Q7vz(7nU2kklc?-7Ct`;+c<~6PRBQdO`i77GLjM~XMjlUpQv)GCq?}u z-C_A(bXWAYp#jHG+Ql~9@>kopCR`53GO-sYY1TNyXnI`xp&Qx+~MwFVXO8n@mbYaeC`p3{ug5Efr$xhtbNRhMr8H z_9Y9<8sKb%@{>e~RVE5deQxo{4=-|VKIi;7zH_^|tAIZT0U#QNA=&SLRAcP$cz%OD zJnfK8mcvFCKy*{z>7B03bH{Os%s&-reLm5}&`%A1qm5q_n|4m5S|JnhHld5!4L17v z;!_);m|ltPxG1WCuHo-H6W@lgz(b-k#`MbEh^OM~-a#}KTw;!HA<%}x{ z)Xn+uL z#>+1v?ql>W6m-a^q;xnc*$j1hr2HU!fO=RDIKU79$ddi*FkXXf05JyqT{N-2hX14> z!v_6h5z@#Q1yC|42iV^}v~7FYyxUtA1T7ty#_9TQQ^Polj?Qhv(`Nj5l?igzn5t}X zanNT$2R}e8SDocv_BsVWyp!*$t}an#Nof9;9}rrM%BYidr&Vm~cC~A6utXC9RR1!7 zRnCKOf3~rm?}|4OXtdV~JIT5u;HZ}#t~*JaI_SrjwE9&tw0#@&;5#lir5%H`SKz#- z@0s62Zs>pS0bO-Ne2p7Bz4t6?)B0K8h3KK?$FE;;wrFAnm8?-XaSTQ^O0m5~Oh+J) zNaU-QMVF^#%j+KhPxbU8joBbfNj#)AFe~CL4{L<{o|)@wN8#cArng?eYLe7jg$O|3PBF|rN5-|j;C zSu0nyhR=5|C(Y--esh#uR>~6xqq)<3Y)8u?5aT1#DRQccPDkMGs3nC}QWC-gcn=22IoD}l%^6aGJ zojhM_FWr-v_0gDYEp?`9kvR`DH=Fd%LG6dT?haG{V>qdNW~opFseF2AvV1z~`}9lo z$$jQ1QpmhK@PoKO)LZrW zN*v32g)F^>%; z|8a^A9jz5TkZ_+s(JdnV{rw{N$+`yl`pMK8PujEV^inLCPj&wy$?e;x-1kC(_?5sQ zlrvxTQR4yfSp}ach;@HRg_RUpR&tv@zFlXaLH0k@l5qy4e6s8G44<7u%H40_rJSv` z{4X=MKWaTIPE28hMlpPT&-7JSAh!iHmO)BG1Q53pedPycEI3(k8A})vlE12$92v@e z@9cHKAbJjBx%i~;wfHhCthjnQA2Aj>L(HAr4NdvY$?*TuUqf^h+Dx|1m_z}dkIG#b z3_QJd*duy3qf+VJ@O(n(azFgj$++yzBQE#TusC|L`(A>eruAlOyw#!6`3}sU03d08 zK+qo20qN@4PFqH!eTTT~>&G^_1IYI`GBV~@M;5)OP+iG}-=~%bcG!ae2a%Ug3L@u* zDv??d%jDbdJjBc>0{8$`MA+cz9 zil57o#$&Pqn>T50^j(F&@x4|$D+51}VcWPkurR)yBFu&JJ=d%ug4N4)4eOY!)!k_~IXBe3pV%;UR+*+Esly zS~4M82d5;u3U&xV*R3Q=tnT~1pK*5r;~fx}Rprnju78tn^mKpKXI+7A}y->fzXUsZocz3(qc zU?<-ceo^dJ$Se@%OogI7(Ex^sQ(DQ~h7jd$J!rE0R~Akd;^Ji8ugPDF6LbM+GRuWC zVZvolNbRWy=&cpI)c){yp{j$xqlMMS-qWX`F zG=kV@mc3W1y&=f4m*a;#!yzCC-&ZlOnJJ(|y)0}I)+O!6E$>M_+`JaDoRU30c`Vk(J&nXGZ+>bp6%j)LhWxWIeL3w3W!x9hI9yB|`J{?qeFX)%5KMfAuzYU?V#YaO zkBJonjU`!oGH6~y#MEwQ?8z5z$jV50x;e4b+MuorsFBz?WQd#Nqs3 zQ%7T?eq|8O0C9%?G@JI$<}Y$*e9b&o8fCsbK`ViDB zD-~r(1vG{{h8pR@46~E1$D)KY>(c7AE%*-XcXN2}+9c1F6fh&obFQg}Myo$Vlk%Lo z2f5K+t}68We*2ttZ^e}4`ec;bF61p|+*C?28lWG1G5Xm(oZpr#f=1ujS6S!$;a>j* zo;=?x;2^qBelbTy%vC63%v@#tquTCQJ;3U;M>&ke?&YSyD<}~^{@MqOH}Ez_gB0a| z-#275E5Gct<8}yfL8ti=U|{=9E)gx^}T%^thteXuQiI~ z&K!w}9lco)S}@_A*|RLzoy}ZhBH|mO_mg`(cdnTLo4VoYIJ_c{eoz2V>5`DWTL_xW z#rcC247m+!tdOmXo%{ohxzV8RR%x`_O+z;$=5wU(k6nIteHBMonCUfN!Tl;N6abkDt=+msfNU;SjwA`R!t!I+W$nf1LzM zjA~`tYV$9he1i*4#KJjHi7Wlb*kDpt(3&E9Atx>Xwv|y3=1{`}z{Y4`038^lKRTk+ zPhpm;FoSdakrY_Yqy@R4Y=!e14HWPJn_jey^GPX!`!uC^6WA4d(eII%P#_BDgob41 zlj;(;4#yktTt6Xr3zYu}Tfw$SUtYy_Gpcm#V>Oa?KzFO|*6M?Nfr^$E(q-912E!_Y zIUzkA$7j|JI-r>eZIXXuCp5L*Y(hs^jc8G5#RZX-_UC+75tJu*K23e@J3dZ{n5A9~ z@mX6ZT>Ob#btenih0QEe>NGyp(lp^)8czAkhHQT~Ul?)JUi0PX(u3MKU_VeXyPs0M zCC+l7`cnUsBeV)F&0IW%6SXHSrq1PNPnPA~`t17HUVhWmoLMbyJrDDY>n*`#wdg*M zuB^6UcO;xhY0KPJA~-nagZ|vB-)$SqJ6=Rzf^zq{ z0)A4eJz^ehJt))|-#cQm&VHB<^4B^p@h$DC7A1d8 z1`%q5jL$ZpP0)D)&}{FI1sx-wiJmgHQ*z{+Fg|a>z!_-BFj~fiI9`_fn6_l7+X1H+ zXK^7e`Dgx8>9Hs$G2AE%fKXyo@SJrY8Pp>{b9%3QQL}`x(BgiwvC(UaJLT#Ng`Sp3 z^-N!QTCfSZOn$Hn=Rnlpl-SzquT{Ao21G?koig~O8QICcx0?A&NFHcD7Mp$d3(&#? zwmwK>W1skN(bjutS!Kd-j$D8Aa628N8E%+$`OurZ+&Wk78)cu_=nv0AI9;s<_ zvM!8VsS`H3^dfnsB0)>{u$I%%OsZeRKYxme?^b8P54nK&Q|qMFfDjLE%nk2036E>9 z3Yxer3y5YydXbIXEA+yI7jjXtO3kM8V{dFAAP+a>EqBuj)ryXWYDl}!d-EWx$>Y}r z?`d=9zmCvI1FmoPACp9dD^~;Lp)G5hVt7QgQVKYU+CrzAQ1B$!A->$r!gaB|wS8-M zX9pQXlSRptQjQMKS!lVKc5sRgrL&AJEe|mz8Ri??*W{nbk%)X<(ioGb$A^_B!We=3 z+02$4h!h`TN7LUAMePx_QZ?F%F+`PzwpQ_qG2}jbe^IpiYmIIpOV5$>KkfJqI$zza)dqz~b2RsSJ}6bgWA}*b0!24v)zhs$0oHFA z!bjV8l-5dibGtl`uz&y#t|9Lopn^j=iiu~KsOK$X&qvMaJStsBg$15hXoOsyhFj=N z!d_)BENeb%I(<;@A#0;R zyg`P(mdVhBi;N%o^2Scv9$8qlUD)>YhjA;ngk0?z2@+VC${wE->`QDHy>GingWX?x zqWmsFDuMo@en}S{Wn36w0QdMl+$vQue8*vU%bf}*76$~3|5G{fbq%`Sdo}4D7%0Km zlbp;E+-YuZzWB}cV9)W$hh=SZllfrfQOpMK^pxO)%36qOgdizBUF`OZeJoFWxKaH_ z#bkPw3y})vJCsy8wYYfSt(f?!7ma-eCe+22a&C+65=mPjOa$d{C*U$^C(OCI8t5mCT^BD~XsTI8h3@KOvl2_OH$A(Ih9cmgTSPpOA-K<4uwMj4o zEFnC#2Wls#!&)iD|LQXsjI_!Oy_bg!E0_DM@n6@4_(a zGWDUo5`+S*x*Uht2Wf%9QNg+Lq7*Km)uQ|gXOAT%`XwGAi%R*Ua!M@Y9W#z_%r_`w zoz|x4%;DTh;}w))^N8bBRodan0?a(vwDCbhw;$xA`zRW0WW{0V5unYp9(#P|1F~|E&!x81+5%52gIv~_yra#nfP0+AI73q zgS%jT*~2w6(pKsS!YAtgkNIPxFR~pO3>i3JSNr%$YOmDzNx3n1&f;7J24X%x%-n#?e2ZBc6fkh+txm`Cdp5>z5hdT za|7DPRC0QJJLl}xgb1>JJRbgp=$cM;p5nGV36wL{&M(VZ+v+Hit?@6{cztH-kzHwO z&$!LUm~IOtQs7_+*G~TPsM%NPf#R03!Dzf$^0FTaj6*in=wt}o~)Zy)i_)Jfq={CiSP(( z`IO=npgYUz$?rF-R8yYYs|8n~Cj55tBk2p4M)&u@x0&OS!f`FM&jTE-rZo?I2Pj&q z7S4=et$y2fwx9DZfA1DiV9eqes&1iUMLc=_?q)=|bn!8RE-kk~DlF{5w`0mktn8sO zK4=x9Q5qd{Kt*A+IG;)R(#?%HX(#X2$t}P{X}aM{W*^$(r-=Bh?Zf?r1TPXtu7t`F z4lqu^&^~hLX{n#4oRjW16=^HW{@L}69}T8Plh`+Ot&4R#S5u$ranGSy$ay&xQ2FO{ zQU<2KLVWh@%RN7AEa+BRQb>D5`)c+v6(86i+L7Jt2*NTUq;kg{R?FUYr!?fIwlmDI z@BX3X9~~MFW-&E#FkEkiy3}1-{5(ar8A(2_g0lX8S9?zA0SZW%-Sot9Ra4FvZo@aQQ=FVv2xbpPO z36*NlKWdt8i`$=WgFEmh8uD(>l7Y!Htvo0DQPTGa=Fs&h5vrgg(@oX30lL5?t3YE^ z0L~ioW|6@{fGBq;6qkA9_891layr~wl8og*t9j{Uz|eD2du#P0`lb2t0CT=(>W;~~ zOz@=RLyPnBr-Drjm%}$p{c#8i)U{neB}5Xt=fg5J1po8V#tZI_67=#z(ozTH6f<2% z=yKFT7yo!$x_MQZLJu!BSn zS~BW*xaq!ojuv0vlVpVspC0^Kc;z&xc^`6g{OrV9D|`^7ef!UT;qcCSokGrC>Nuy{ zYY${|dzpB2RQ&H*$hlS)Z>x{XL6Oxt@9|>&OTEX_tvEHHr@u36wyDuQSF-b>OxkEE zk_WP@Q-@tk&?A7sprFLpPcuv`?|{-HkVfG2gHe%o(!uhJH^;N_g&gIz7d5GmsA|@* zN;qqjpbzEs%$4%{U2ScxKn9N_dxzi2O7KUhK+ekaF9W8;)3QR2N*_I#g0Y3o`#a*s{z@A9|;(>x8=iBOGs2x z7*)N7(1{i>MCuIW80{F_Nb2#T)TfOM(2e&c>^l8D z^`6)X18Drt8{9D0`tKm+faMx3AD2vRB-{3T&E3r7_s1s2P}<@uUrdK>c&0qc22xd8L`9 zIrySv3FXUIp&%GJX)A{<0s@LqykjfMu*n$00Y7BR+ zi+ADBEwdvc6{^9=+*7KPH_ER;vu?-6#ugY9gpG~O&c@fIu$u5oU565`V zvHxNX{att_Tkmoyu#~bJq4HW$2+iU7R97mEL|_ob?~i%ucSj_Gu3wTrbv9o8<2DF7 zf2!w4ld}MjxHxdcThxWlA6#Yfs-S%eZL$}G(Vk8%rD%;d-$6cWt^T&W$}t)c33uF`0Xjt{24ZdnV6WK#GaOYk?#RjenBA}#6JZH zG-Um!ZG7Y&r%y$h;AO_aJ3_owGTHF{(JWC7Ha(P<;}#@*gdXsWgyb%k9#LN-evrkM ziyFQ7flS&(qgaO&fFB@2$A$mEi2D2?Je|14Vli>%RIl>)V;Ue7A(kJ7dQ|#sm@&X& zVU*-vG#an@lt?v5;<(!U@05ND6Y|#mspl)Vzy#y81zuI6a>k!NHLTDtj&|B*!2tBR z$Of!yGXe#5?2@aB9 z)~s#G6Q%o{%~!j_5A}HdDN(ItVqyaB=I!mhbW@d&TRke0BlMv^(2ng()TR%t1hFf6 ztbxQ&!PFR11}azAl|oNZdG87eR9G??;L6JVyA#%M>*tw;IFZB=9GRsYcwUF2u8YKq z0RcfB9Ub^51JBvn*_p!^zPrW{^*&!bL*wD#7##aOb9>i7^N~nVXV5{20i!6Fwq|lq zK;Un5bj;iKf$;Ee8sjP#vlujz!NysEDZ*K}{WP^Rq(s^VA#Pnuc?A zlY+`LOV}_I%)B3JZK{nR@9?8Vn`?IKtM#G29YXu@wnu=x-gy~oJ!<cv zopo}%r<@nvFoFWyQ!i3*(NI&m?r($9Lul3Qi zE0DzULK@~BnfoWJJiluGFo5&NCP8%S^X_?Pi{DL-@t(z5-t7|if>N;y_EJ0+wMfcI zK1`g(6V-JUe4@xN;p~xq4pM(kENZP_M!*8FuzUgiV^>Mj&J=D`_~Uor<^H( z1_>}~;EI3Q6cGU+4}w=jy`-@m;hcDrLh>q1Nkfm1U0q$6&3P#)wn9`NKYn~4``t;n z3wTN^v9^9pOt-SVQ{xO}kYpcTT%^z;l_!-Sd?%8jE|K*6oj{hEnc0@WugvKxANFw% zHbJ5=@i-#gWl;X{ByjsJG>e)lw)A_NLMA88FgYu`cc?_%aN7?Lmn*U7ATSQjpuvYe zln2Zxg=n<*`zCUc4Hrc!x;A;X6wa|+aau~s*bk=>s89w6wU4D+oZv6)Hi>__aw!Y5PSNPe zbDEAa?3h{ZPTlUOEds8h)1NY+Hp9P-4P@yK zQ}^}t)p*p>Asu*c#A`V=GGyl?L6Gm^^F&3}B`1r%3*K=cTAO+>ye;tNy<@=-{q>`D z?nD)b=&vd)x}T@!e`l2L^%nNl!Qi@nB9yBt%;5~+V5DnwB>{*5=w?al$%zGB1$LP% zdst55kDL9wc})rR-2W2A*=^v;HfkG_YB5)id17IH-7g_}vcH~+#+J?q(6HGtgXDFD zjL5!KR!1kQ{EL(JJ6;JXQlYr;Hk(>2h?TTX#KK}Eohf*wtE;QDP(w#}b$xMzjhjg1 zxSujSTWev!wPnuC)Fd!T9h7+!M}%3B!}#^Z zpC9lS!Y!+ITWlD9s5Ri*9E;%9+YMZ!Zk*)(_oFf6WSVr;k{H0wuU$4^tAG3>R|lv* ziu80H$V#i4B?Vsp1cQfPRihCR6R#&i4JZL1f=GWJ9RNynD}=kFO1n@>402k<%0}y^ z#zxe1a>)G7g&6-mrYYtrWHT<~rAa4`!{|R}y1lv2Wx%1S6@U&qN2}3KA7vB$EIHhW z!N;a;W){xz&MrOs@DLeC+Yxw`$s?&1i@UjNGx(ci%xpU8;ChLM6U~1+#fVKaTg>54 zzGPf=j67gw+=GmqKke)OJ7FWWL<}S>T{xPe3PQy@I}+$~GzUDQFK@!4euI-W^{YIN zhd9@a8F8U1#a~Y$utzVky`=zI_Pe4@lea3V}Jf>H9&lj1VXE(gezc=snk;>vCj65k*M@2R^wz z!^@?(w>$4dx4eE;U81}MfCPZQ^FnsYxE*HCa|PS3-Da&kN2@fSs${YL*GfUHj>N~2 z#o;GM6-8_HcSyJS)CI^$s|DRuj&e+tSlmxFlw-d(=_zg<#u8IIhP1?=zDYf<#BWdV zudc4PF=hK(i;Gzp7@$oqQ<2(knqvh=Fgs)ewlx7Dg!wVVTBfrtP1cCI%ARa={wz?GIMXve5j9(?tJXqelUtu zp*yA%b51a#u6UKFzg624UXKB0vXu{FGw+0J&mu?xwhiGp%1}U{uyhVI6EeK3nHEwTl3JLl(xyt38h-d!q6a(T)G7j;2edNEQHo5YSdd^o<3i1+vSRbj8o zwQ#+^W6R8F3LO=PPmZSzJPp+$07XslKdb+X#Nfz$_VkXBh7X=0#+Ybfe9Ftsz1d;? zrWEj?@q_pLxLox`M|o#{2`dw>?Ov&+3U$}h$#~;_u9W|RXYBsnRnL{>awo+3B2`10 ze*daJ*^w>j_w4L!V|#bV!!;^GX2dXc{S|-#Ep#LbM=l3H#zjZB`y9+%?oH+e?pIJ) z_!rO}py9lnc@KcAh>Ua^j#nEe`piaV1wy$%33^t&R(yMWK&(R%e_qK_c0xh+XnTsN zJ1v<=lLiH@A9u4@2@a5;t444i{V`HcYs;g<^708$NBpcXhRr9y(^K|6+uomvP%kep z8*BnT_G5J5%}=N~c08N8is9fk^CvyV;IDD#?C)G2@;cyqMW z=JoE~mf4p(D>*^)nr&*<^G?Z-g#-H0@yXlBzXDa(S1p$zZUcu=#Cfw)W5ZXOr9hYs z%!(d|{65?0-0-B42V>2$=BQB0Fb4XF6M$&# ztW>_vD;tQTpI2kCnf;@qT6i7FU^E3V{MTOz~eP$kkkDmPDY&*TM@Z5ZJg_Hi-iin#2 z6srJ?Y@_n9C2sHwuS?l;eoIJc8wS>^5H_xVG>eD7(S9eCW)0+b#2-SeF=kSmY}*Sn zR#((!oU{&9DB_1Ezd@=^;b6u0L(Pd7Z)2|FZ@7jk3MPE=G7XLa>FrrwHO_nn^zUH-%-hi z2W8dNKRLinN~oHXLoDPy<+nh`v+C#UrG*?X&Tg)_SKuf2yVN_^=Rux`8?AF2s(`rI zk9YU|ExT?rgqi0P1Sj8eENem@%y%`0m9UII>#$wiVCum-pTl9qHmj8M)n|l>ARq~G zao94O`Xu*mJE&mf?nU0qJbtaN?O|it1%Jos%bQT2=&X+5`p~^I;TYMxO25T(YgxbO zwubjROL_0cM-X-pZZ_Ko3d?Ru(=NwR{F-7jP56VL(Q0(y-A7KwUk`>np(iM%d^5?b zZ6I632bpTH>MCvk5G`={m4hlS(OO+UDghIu+N4Y=%AadU9a3#ebPp~sN4^l~8IsGZ z$R!ek+*Ux{E0Em1`Cp0)c&s1akYII*j~8=b;vO8yy!FpcP~}chdz0E6zzF06#NjwV zB^L&R!6(Va`kN%*En!G z*-6^Vibk42NsHZ+agEH7IFTK;yKMc^aDO`}Iue?0`eQ-Y>n(X7=I>up(Dn$T5u%>< zjru>n?9Vi*HA=lGbZ_kuW}bKe0o|=i!p{*~Gdmn2COc4+5Rs2*xEZ~WAF89_)j-!^ z-OS3zfd^@At*b>;5wsuzkspYob?*L#qCG}A@J{>a&)_grwq`x*x8W1wfND1@+EQF& zyG>K3f2Wzpz^?BI78JEJ;U8RB5##*tqNq9;fzdp!{KSa_X-Gm;2;5IOk9R$$o_;m{ z4-K7q|77p4a4#9i`(&DZ1irL&n>Vfz!g1IW-b$8P(joIX5gka68>3kw1bX}~2~A7C zr4jeV%EHXskL$eJ*tD^p`d%Oe3j#iamA#(oLEiqsa7p+6?*<~1YCog5YG6yJ zG}lMj6Xwa_-s#!AoUVX}>9R7vZ`E*t)w#=+^Q8iAk*+B@p9e32y&zu;ou?)eA;x~f z;K(;kUpICToxB&nDT3?Z*G6&UgThI4gh}Y(-A2BiTf3%l6jyh7%Ig`-j?pWx*`gXEzOe2CHsxFsV<7<1R;v(oY)TH$J1ypf_93; zcV!XP#p@?peY%wXa;d&hp;3zVb7d#J9mA6P@Pz2E&j61U-9C7B$O2|tyM*O14-dB} z7iBe{rv@;qmJ1CGrw*b5u1FJdG=|m~Hz*3tmB?{BoI`1xXPPP` z*P}I1{K{_@Lg~W;KgNgqc_yH89LN)?lxGD1BNsMSQTLJix)GJCO}d+yR0H_)yd*Uj z2+hv}hz?{1`#A|YQCi-P^&gl};M9GMETx8>1sol$;J=$*FQUF-@mc;iTCedX8j&N8 zQxj92>@6uU;Ar;fUeU~R(NGhIvuU%Yk9Juv@i8BH_x14Jt;?_u;aUVS*1KTHBkf_I zLqS~UXdMmDk@|%2dSRkqX%d(a9-~;o_ZkGNJ=}#IN;e(bh=zEM>+ysIxm2JJ{DQPn?8;5>N#oL!nFs&}TKZ4Y z#Qe<7*sw6C(9yk(WoCB1NspVoZR4#;cSUcp5J|~rbo3;9T{Gbg-I;&aDiq~(Z(2XL z7*4+?)wsX~Qtww2^K{BIbJ#R8y_NA%*V!HjLUxWDqvw|$ke|(>Qg9X|&JgsT9J+8Y z{Z#jJMk+es!D^@b)m;b;T6dD%-A$zwbX%7_wZCd0mP!P?f=sM10SV#vsy|7g5|LIT z&lqS1>@0lPZ%ZbMW?Yx;1TsK9;{%e{4Ilb9&#XkAReWJ(2t?frMPnOpLyhiX#J^y+ z6T-aVpW=daw9ny%RoiRv13my0;~(R{Q0xDo0qgC&G~KJrr+-cnM*z{yBbN+b&wDcz zXw?@9^vjZQzq`s(FD09p&<=7%qpw`E40$ZNn^ckxb=S#B3L!3&<0!REETI&e&( zvf|u~NOS6z#(H);gWfs85O0tHW#vyu$aIRrHMlo;Lva4_1qo3#kr#%76O$oGNGM%6 zOGBx&b4_WZmTb|pT(d|*+|-$TVP3Y_)szfo)7@@!^!{JVzb3~=vxp5#W&mp6@&P>v zTPIv z{&U{ncJ?bW>w>)NIP%OD?XAS%=8dZ~k)*wcb4eSY;3`o48B_Zkq@4ENY2Z8Z9=2k{ zEWBl#ntn%-pf~dE=2N%0`%V*Q$isapZQGRN&iRCEanC`Zl+}bG2j?fx`h>_@<1~UP#Ny@{eQ-1f7h9sQmQ1mZ@ReN*TLtADlNsp6 zg*1%O^*pbDn2hI4SE@Fw$X!Pvc~Yz1DEoY0WoW-Syv3|#mqPZgB*+4WTW8YyI`H*2 zZ|6_Kos&Cf$-l=1^Bo_Bq7l36UV9;4jdub;<;U%5DJjhkNBj33?fFO$gSdFcst+G6 z0}qc&ka7B`3ACg4M=xmL3Z_w6f~Eh6$NL49%@J_cCXy5w{txU1ms&SK{P<3ZDVDr1 z!$6w9Pr0M@QUT;LR@psl`cnZQPLxdQ^!QnnVlDG|^%XBlDenNlN-gnQ;eom@zfrEv zxA|W1X81+1XTRjw1Tt-KdWel(Q_11?GLQc802Kqz?NM=`AYvg>U1yJ;sj`{8#X zMV>JR00u#wiv^#2vm5O6dpY{J(WN5^f>L}3L0$?0{ABj;lG~Mj$xy~633&Y8lf6M1 z3j`}Pspppya&-YcOhjNltlr@xlRSA;3ynzD3q{E`e@6J~WB0No!_%?V5oRT&-&PTn zdSvR|s)^i3{l)n-3fr^r7%fZf(SQKSw=?JyCNUX1E`d^qM5yV!5uW^$^KClU*Ae{ zRFe6lMDvv8r4p8SfaCeM?e1D90J`Dgo_UVzi4AyO5QywMl;8oi6i(9e5~?LnW((A| zK*c&-NY_$8{rTC5`5l_b^Uj5qzf#V=E|yI;9R}o3GWgqy{JLAN}E)gbbF zN93f52ofE-bQ=I^zy}4M5}LZgW_#Z=`X*4z@{0IIP0!yZ-M$imKC9fvxgA6crGm{x zw4Gg4YcBF#lcUf)KZdQ8@zvvFF1QF5!S5kWq-XM5$hA1q-)Gy(ro@RvNYb;M&(a zFzWd|r5y#G1~=%T{rOo0z`v&$qne8F&k9xkb&tVVP|GrR<_vNYw;6?~b0AopLwrB;v;O9>~Nin9b$etI# z1V>@wh&>~%k5*+B+qtmk?>3nMrugvTkRQFDFLrUsFvCO{VZ*W)sUNU(kTG)#)o2bF z*dT#lhY2v(UsTx0IME50ssg7J9Bnk?%+f{OE5zF*e(?#W zV{@63t;+J{k1=_qy|RxXda}LcAlr&H6=d3SgN*nH`@o%)UmqOlAbWc>xZOAq*ulWJ z0>A0BAX{06&6NC0jsD40(5(i2h6YAeHQ+4IfZaODDK4_Y@_J3$#cz&%gzM69ZfQ6| za>Q-%-zu}drBkOrcf7!RJS^^!bP+yGrMoB0T>a|Z>M_NCp>s%|ljX%B1%QzyMePMX zs-Wr&*xq0bYv?YN_dCN=)WLuP>sc)Z@g!4*(jL5XoEStFm2HfF)paDrAN&p%LMH+r zd=OEE!NJ0w5$R$qe?1*G$N_#2JfPYI&a-a&b^D&3@T7Ui$b5gc6po4E)!e>MYMh1G z6_yPpTM?=SVPx6%`o4Y31ZxPKeLB~S&clN~AWIfQWb*J(d!MU?g2*-m%U(P|-r_{q z?u3pq-}o}tQ=>umhje-Vi zc(5`(S5Y7`afkL8JW;Ix99*t#j*Dri=ZfO*(%U-w`9%uK~(Mydd)I()}x*|0%|DL3w zB7rXw=+gqcA4`Q4f3}L?B{Wk?ux;$J=Dl3G+&LBbg{;0UVL;u!%}>@SX3-L-zGzv0 z3GkB%*IxO-ybzPd(WcInNGf|DrB-r&brr$2JjO?`@*sKf;Ew2$aKInpEhAImx{_5k zs*ga;19bE7(Fm@tc5_KsB+7+$Z*y#Ll10d=9MV-?pe@c>K)ma;wmQ*HKO2 zRZ30Q1b)9juO^t|vB5x@J^>6e5I>hgqLnWigQzu1ykyUiFY-8^Mtw>h{MZ{}SRkpA z+rK)7CyV^5O-e*YX3(++q-s6o-9s(&Q2}lcfZ``4{Ep2QDQ|yJ@LHg1tW7~@mj?=$ zyjv3`rB9k=f*I<)6kkw*=PU06uR}59wV|Q%Z;NbhLw`rSuCr*x0M0(+!iyZ*1VW8A zR-aWVOJF^F`XOl4I`tZ)Exnh|s0S!WqOJxH3NwgbH43d#P_b0{h13-RA zo>{&A!>_-iCmM(k<)&A8-`>rT$Or+?$3lf2uQ@B+AEIQE(q2+7EF1N6gUvj>*Q@eM zB(S}sX!z{6FSNotE;t{*v0W$e4t1L~xUOs&(5OiFVs&=Ey9aCGLI3`Qz$1>ESgB>x z9TV;qV(YpXAxZMS!5eZExsSZ*Fp5OZujkniUf%;t+RI;wFfg_m1aCaiS~esW{-T&2u{4D!X3=_*?ZY z3ntnPqQZVnTHKcBnoztFDlRkMxkZh=3H<@Fzr>1$qR}H zEx96PW$^w)DM5oJ0780-bUvmyOWO#OXJtpZFF=)VLGU0H$MiR4nXR|ItKQkZ{t=Ee zU^Y2B{@9y{HHKE-=iH~{dt`EF-c(x%G)s#cGD3@si{nW&7bv~159bF5RUi)|8GQpG zz8v{Rk=2(Q)RYkdSlpD_>GeMc$uizivc0LmcyjAh>zoB3h6Vbc&knX4a*zg#fMBLN zIy%P2<*&QcbcBe)IHCb2u=e&;bs)umO%hRJKbQAI%ZD%>Zg~K@tZe{w$7(UNjs1X; zwE?q}6`@W?Dy&)%!^~8nYVn<_n{_ zJMO%vR`ZfQ&y?lSw8 z&xaF9kL$xXCA#7#tIU3#KOa{^)Rbc3KDQc_$hVZGGH-DCwmmP%gl+Vx42^{xuNYJ3DVPZhF?m;xC zwLbWVLM3=GhywmFp!yt57g6PR@TD44O7wV!O4APArR;dZY?&N$z?XR*>@`;JY3Orq zdmrmG-i+_n$>fLVw;!9kCNvem^#o9=HlVYmbNgO)wajBQ?ns`2xuEi44TXx3C<&S2 z-k7TjSG5D&hQamu-#Gw!hw?t{i2+>p4_Z&kD|adOaZth6D8yT>q!WP+Ra=Bf8X!zP zTZZN<(f$WxXW0~2)GX>fxCM7lg1fsXNFaD{55a<4aAt4~5P}4EcXtmE+#$F_aA(lr z&imn1ox1m&s>=_cYS!LsuU_3xKfQit;qM+BQzoKha@KHtz<_mx%M^dL^wsQUL6htesYiT* zk4oh1L#BDx+gn}}^$p1bSi`3lQ#;j*R^@e#crB)-&+`462*aZT`JY!nzaLkmX z!hh|}8NsJ?$=4*BxS}Q0Ey%e4b9?a6Ob!~OjLA0=#9x57GJiY22)cbW7aR^rw1C8s zbGfZV<x} zPtLvR?A|e~?dEf}w+iL;X5I7?wj9!R$pR%hvF?~O8|XjBJf1Tpg%K|LYpouj*bNy8 ziN|KLt}m}uRzZh7~ji{*Q9YWL5&19i>XlIS99KQ64UM9hY5Vf&shL+_W=?Gv_itZX{$*Xg5|zjM zF;HX{eMDu}8!jZ>vs?pIW1#AiH7+k!MmQ0Tz-vu+J7E7Y8US8mzp3V8uKq}jdz!O> z`4`X~zVwN+PqKwof%(8snsXBVZ&Tl&uhhZ9fo zr)C=28oVTr?5?e?DHdpy&FLS2GryfI@9*vrhcztF7o8K(`V!{qqX7YN6lxyTY$LUH z($b(oXJ0}{@&lZvB<6r4NbvVQ)BoYXrv)%mJ?^;mLaFy3^^hU`iw^qbT36^e%$mDu zFepThV2a@?xs<5$z70ys1edP`nlI+=1fQx7ItvSu#t`)yYrTZw;>MLBgmtuTrg1tD z9&A~z_6U4@pRd<#g|wo@Aw>{@P`+4Wq-(y<-=Zb)O_@yzFF$@7rLA!iZZ1*r*Ea_R^Z*%P_|rN#cy9$`Eb=*+{fqjdVPG^`?qn z+J5%Qi|5RJbr+!;S!--bQlR7D;DCdsiUqZBQ(<*=bt5Tgq?TT`-_A=|CLB&%+=n8Y zPIYC_N?~gQ|8Be+mU0|o;S0*vSIah_8;;=V?ae}nk*Fv;!zZgQ3~#*j^17V}`u?zr z$}5mD!(b~6IJvkUPAx*e%lnBAQ>8gm^--M>i6R%PcV=XJqY)-V ziiXRA#>V@XA_{&QE0gv#A-3D2I_X$Bec4@?hHqOJ0v)t($na7Z2wz1y7S6KzveAM* zv%O;!r~}BGqbRzZCu~~|4i0*HdUEfobXI&;8@sFFZm%o$S674)%)o!XkL>8ndVm%j zuhs^}3B}C*Ku=fJ#QzQ^6!4S$%h3DHlg(wG62Q)_=rUSLNiGuYCF10y`g3UK^b}tE zu}<9+!UpbMh!!%MS-YsvFI;yj7SGveou84Y57L!~b&zAqJ3M`LDyV>Uerh zLc>_!pH}_iDX$Y-wMC`JPL3G`U>Y&-<}iJSBm4>o7Qa=U*8+fat=}$Ek`QhnkXs3t zn=E`f;w#a(kuWkPD;)?o;uHSbSrZtWF+=ohpAPJ{GCPn_5&j1;%EA_sD*ObMvNwi! zj56bH)HQ@4gISA!&Z+DSHXw5#vgn+AO>s(iT4e7oAU1MCeaCDPsm8<}C^H6nTvyGgtw{af1eZIK( zDW#4E;30(PvRVZm|HeMf{=cyf7}BVvYfFT$zzugNe(#$dwUcSfq)~&G^#SH;uL<}- z3mXvAoNM1Z;d7HDJ!&J&VDprd5a3aHN|jQTS@R@%i=~*m@S2g8~AZet`5fVgDj_6StR>X5QRzJ z8hHFbFi7t@Mi``FXa7tZHxn#=@mSDeHSGEw34(2X!f#`J^uwR;Gwb}b%kzF3(SZde z>c;V|$j;_GZ);gbT9>p0Lohvn&rGnyd$6?|)_Q9-eu_GP1y8+wXuV!^xXyz`L-=ad` z<@~@v1VKST9UUDQ+DI+x%VL(h05kNjb86xJesm#I43PD#n!`fH@t5#CbqT~yPDBI; zLn;ntiX?AlH96bQW$fKS?IZw@!>rI+LR4wtj*R|&>8{jXAY$9CU($FFpnWRAKJ(C- z1OPWD)(O+J1@mE@^3H0W*e)dIVUCBr!P=FJ)xC9&-9cgf{QREmg)^AAY+1}xV_I~4 zZu=Wz<^t+p%=0?O>tMYzvJM6f%PR~3piDLg0H-9W6amM%If$c(`p{r4C&C{>Q-MJ3 z5oZ8`YtOe=mykxllTfGEbh%fN*K65$5U4z;Iqcv95Ei^|E>~-_7;JHUa7aTfCNC<_ zIi)4#MT-0R7{U7?EC!aAmPR3J3K4du0sg!}ITrEcJCLcB;h^F6z1x*+)F;dd53i?0 zG6N4r0_*ANV&4m$l|ki(D@RTlNsd><+fshgV+Bj8Th*3o-Iwr5nC=wiBA5dF)aSuq zQAyF_{;*5`W=!al#nNVGTbxNs@?#3P0#dozF zSyIQ~Q|w084L5j`eoVL7H-&|D-nrN{mu0ZN3DHqI(l&O`@R1pI+YJ+T)in8ATgmYb zp2=u^4zgjb|LLzMUY;cT@qZ#vbirN=f+m&gJ~iQqo^HO^{end}XaC-ladJ@IEIIbi ztyNH8-#F69F$WAiLI>&BPlYmbP_;~BH#IH0rYD+iSJ3|__GAuqyH@Ftmb?#PT6tY*Vq zS24%`-h%+{wWq7JiOv_^f^bdiTyvAOo26{XGPu*;?@45k2T84@1pPIH2}3Is5My@2 zxov5GanTS?8?JGAFH5YEv6DZlu%D8U63lZiqJ^aR^6>0|gELY2V^vIC{KT-TxR`18 z={~Txw>J7CBUt$h^wfU2!Cdcl5{8)a;e)Vz?8OvnAg(mry|4I3zIYgcR?7i`{RmQ| zi{IEV_3(hg$uLSWPp8FN3keAc{;(Rh5iTs5@IqYW1#gGYek6h~tSF`&>=Q@;oM$fK zc^X_9`{?%?wX$-?YQpdu9 zddPhhyVbhlW(+0!@IfiM+ts5@4yV;;%vT?WC7EZ&x%N59qklBqlF+hgnxX)^b+OEi zFs<4bQ!~qKyEz-)KdVJ@6iJl4c3TtHRvH^nNGg@G(q_u)aO3xb8Spc*Od)%M*kAWp7 z##pfR@S3w|ocX)3KkyF1r#9<>>78Qctn$cjCb~^&JqqN#Znrw$7F8`ux!A zS@fD$;vi39t^GQUOfHr^3+obTb%?Xj-<$5sN?@YjN-dQA@w(3@9XfDeq*dG)Yl5R7 z6$fitokW+B0@Tr*gSjkYh8B+M2YhAFWVKA~O#jNTvGcReaPxSxOn)Q`?c&6XytN~V z&q`jdb6nprT^?D3M{Py0$Fup1pCQRrw9!Q4<4D`>D~1``$v@N6z5bygqp1@DxWP=p z;nmV?sR-Hy|JJowTK~J?LK#lQP!4iqAqK0VeXtJ!bYp&zj+)7+3;YDwPIJzAG+|>) z30-58ejj7MXRxDgT_1V#0!TKY57THN zzD5$Owt2}axq`8>HvBRp(-f}=ig!D!K!1ep5!Ff55JInP*My~mO+$fsqOg!g(H~Ar z);t+)alJ23(9gxg{c0XQ^5C)l%Hzh(C3nwyK<0!P%N_U zhaOUe4P_AW9VrMr$@$HUz^3*b_?)QpIfAMvB2}YnN(qtD%l|6|%twg;_Xg|=FI*HG zP;#<3yFm(|h?&L?Ha` zZesV@_8|8J_v1WG7N_VQbX4AT9Q>pgal*Yvk+x=#DeBf=m@HDv=8$!;*Yn;lExAx^ zMpO+ULtnM69-8=!uD54QmFSHkD(ehAH?ehZ(sJO6f#&*|POCZE}xGvoYyJ_fDZ z(hlOIgpj|oq=2rs!$C6{>T(Bkn=#f)v#F}}f5U>3QsDETCc0LCtRGKlx$ku!mzB`l z)u-m4EqcicTOVATt>-^wJ6pU_3uj}8 zFX=}uCbzcl7$(RTBq5>ajb~OgV6&@vSAy1Cm(tzs?X7oLgMOYh@MtWJKvSpT?;HlG zbbc9KjnK#j1A-y6bR`$?Q-85Dup?NH@lAjE`;ig{?(F0`;g5}rc0e%N;GW3`3%&W} z!KOys?lIeiDrzx9-)9u~mI|Lb`U!rZFETQatKw9h$i{t>cSC$`Y>ZQRnztRO2_7 z2Ae$-M+6R?JJQ8mm;iu4GazSY_`BXqBAJc*%C`ShZ6wXMt42fxfo1|B0I449;-mim z@rsZNzTm(wnV4SW$}_PDd>=2`E!ZIiXkrP64lODMGosy!-1;5j0^byHAexi!6o@w# z;_eNBPA15i$Dg-*XtOlmsOeDKWalgNHpGj76$6QwXFgDklhpg)*w{%#Ix<{?&W0A# zJh{vmzYGl4QX5OF_gT+WF?1}cb?fY4gc&Z|q8*0J9N>wk4_TS7$nFPnB?9n`I$JW@ zkmx!)2FD}ZZq&HR!r*D16V!D%7>{7?Jpc0{ZHXd1@_^|8MCs+x_c9E%Jxs+wth;OL z>DFSz1We(m%iWq-psdT8GYU&20zuyAt>zb z>oUKuPzaK*iUDWJ5EZRe$aeg=+z0*%9l?FmIV4>rSZ5LI?^yJh%G;K=j096 z$w|y84(ymTtCgP;?mFI+M31aO$L2>TKV-q1`vHgxHkJn2PaJyNJfCKn`#DXr;< zbf^Ym@k)lL^7q+_wyzsIA(Xs#mg%j%o)Sy%-Xa6pVy)sU7~1L0w=c&=9=?QgH%GHJ7tsSn`;WYLQ3P|~--h$<<}9^6G1#j5#o?;?d6oXEGF z`+rB8wO6tbvc>Ui1@8+FpqXoMcJQb&pdpxj>~{{v#ojaU(NjLrlYy4rA zr&7;&BU3g_l5225{m;wRrGYVnt9ZcSuaKqgR*dGSa4U5El{`k*_4fQ#2N_~|MF989G6m0 zCQW5V(<4JS+Z#mdft2Gqz*ErnM9B{&?~|!%E>r%?$>2ZpJo$>XYIu(qBHAl##pCsb zX0Yg}T;V(#76&IlLe9l9^s?I%&kVWVrc$!diEFQr`$J|*KLi!-YVuH$su>IbB^@yQ z3P#dnmGJN>e8=5_lyb{@-*q|IN``s&b?fKl?YV05+?L{3gcwVzp4+C`ct%H~h9@v_GWWTd*1$amCT zCNs8TVKz6r@A_XGp6}IX4vTe}JZ6dmfPGrY&o1!8P7Rxq-6!ND^I1Cq3NyA=|IG=` z_2-hwibwIWmEWUh+Au>>Uf2FBoM0!Z{axl6+Pw`t}4(s7G~RVwF&9(J$A3+j2Xi_ZvH|Zo!%RI#uKg zA7?!OfwM$-{4U<+L2plJDIZpa>^7sp%v!_)S80->g%o!^&)>^Gt?-&HrT0vX`I+sM zP>aiGKr?L~d*$=eNJLHJy7`^U;KQYwmr zB-Ey5KrG9~d4y|9=9lX;7HxYZ4+idl5ZAyjYbI_|EXz8*if?QU)w*mbLDGDr`S7O0 z*TLtI{JVXjUV<24S_Q7UD?w9dBG9#I2|S^)N<;(LbgO9@7z%lyff`>0(t7SN7b0CE zm3PNRUFqtw(`5h^(J!7eCK9c8Z6CTEW@_Bij!o!&e>(A3>R!gHzM2~F^)cBV47y6T zBI>yB321uVLS0JJF36Q0bi=DR>hrb7gr&|J0cZ+Cy+bWwHwwBq(%L*ql%L?6j`Ix? zYg!tt4L4P7=egmz@Q$Y{nuh$}zX7CgkJN7Mh|7jGtA(~9(lrq)%jmSe2sdQ0An zM|C{4#CKsAy}7)=7MKCY?uqM{G-ZkVz5AzT93i}qH~*XDgK+;FmiAuq0JS)E$Ru^p z>B)3Bsy@H}#lOr0$)^O7+Y;h-nEoL@`5f3O_WZg-KAO49zYVN#?6)b}BP zRJQopd-Rv6-R%={>{=5L_we`8?Xpw~v(iCeufd9A?B4nzt^ttpW@f9;_tco%$F(`bAB>qpCYV6EWIcV>(M+4#dqVc{G|r71*EpM+c&z z?*wz?u96xn6EYwTXAFioLGsHOfk9_Vvp_J+H$hdj|~hjzRsQH1*M#NLTa6r@F7e6 z8IJjk^fm>-Rdlb^h$Bbj0BksU`xS{!Axt3#xa6`5fXs%Bw-iZHNq@J5mAT9jgkmRC z<9nen6Vsl_H!R(0;b|oRvy?KGMjh0|9CI(ClL}$skSl=1(7L<$3;c!8#H(0p)cR5~ z;_w5d`_O$a&VY~d<@{a{j7=kMZkDyTwl|YC=Ka_^HeP%xbTjtBUc5nMed8S0wAZr1`!!sQUCaa zdFSoORsQG+0&p=ZiF-w7ms7A@9D0)3 z`^qnPe4*FoWeBZuU%TP|<28SsLITEFe{b1+!quzW9ci};IrbH?`a3yo(A8`@*ys4T z&e`5q7;V?kUwP$gV!EakfCe&0ipKTn6Ce1<;<8E-4dGD)Wja&7B{Ur^MaZT!2h7=Q zUrZLDFa3mUM&Hh?Ad%a2oZ{H;S@_~25yC&gZ4Ij7{MX&TYF}so1)_^cmZ!troah=Q z;RIYt)s`WT&mC)jDev+(nT7~v_*f7{u{fNhN2nTpYF1V zG%?@?=MIt=*3FY63ekHo>ROgjdaC7e@}3x5u3p(~?8JGkdzD*H2ui3yJRr2K;=Q!W zO$0$g4b_&;@$Bc{*_B1wd9{y?;B-jKWIwAXEamcY0Ep7Je7YMgvvzP?di2A6x3L_fR|d z`gV)l`~|k%Vx9{R>OwKQvg$nP>(M{uRO6R1e9a&pK-i}G+55G3Da_pDa>%eomI=qQ z*@c0k2M4L7Ki!o?$?Zbfm#(C_QZG5lA#Hjl>iu0YK&ttTiW!|^MZ7&>Ev+)Mc{or% zuL!N6J>AYJw7PR+LiYN!4J_97tVeD*gyo9cA+lx^{d!3|HERzTn1 zqaim_S?{#AFIDZbF?tfJ{=>lzCpSeBY-|V$P{za?&v+^mkz|g4`DZmCpV1RY|WJ=7&NV#(yqKK)fPy zhQGHg^Bx6aY&5FB>#}XKdOV9qZ$8J7-W`b?36c+!AFN;L@I7S(O<+YiPyFrpe8HUc zxOPa=8)VDvYj@lTHOaVG+nEwi{m0fKoT}o%Z+mL7*7og0)i9RH(fguxN(A$aY$xJ4 zsOu?_eDSTK2YlbM9Iv56{Uwf87tbQLy+g=i9Ph1t{L_l4ZO&p8Ljb-_ZskwwzD-*r z-}>~c%U8NH5tkOEJl?(DJ|YH*EWI`-dW zX(&;$dTEeshkh94MKow8Nng6{kubme*G$W->^LOmQahQaoc;y@fLeAeU7qM*IITjS}LKwf@c z6%zZhUv*pMf2+v(!n0Pd5rS9)izUTEY0ziK`1GMF;wMysk;WV`B!Af|@^3bJl+-Xs(oqtDbju9Y1dPEl2y-P3+iQF($RQUEJ(1fHqd1 za$7^&2&9N4OfS#ZiS3>@%GQjGtxY1X3HKkXQnK2&+N>Aj7uQLJ*NOeI;6YP3Q^Q=) zaiRPp)PJ)-KUq@$c3mD-kKK`8VQDj*+*kj;kBVF~sI@swuy`{I ztMHb59GAQ#0b!BFz`Q{PNGEBCt(!FP9BDPFLWoSJ?WhjeBN{3>AD zKU+1aGWlT(S_xcQ;fGZe4b;0MLgKg2R5QKQsHWfCRx+P;@;1AMyF27Y`8_-f>o&Vh zfg8g!r=TBwUiu|Kl)!8A<@66_mG`m@C+T;WrD3Nwn?qW@_ry^>NU^l4RzV<9On=6A zFc+)`cz-=6MzZW9VKo=VcLtu?8YW$)0&Mv;>h+{lOc`~9?&G4`D&cBT0>o{!O|;Fq z!`YE!Vd+nJwvPaMz{wU$*TagDhfbYxF6JvNxUj}yI{$-xRc}aZjO6X<=_I%D(ptw= z*f;K)VB8Y95;iBY10DS)dy~1J`beKVifV?p8_R(7HpF>1wCu_Y@Bw?<$=~nqXrxgU z2t-IKMc*TlhrW^ed|4|igAkv&lB%DANX7DE=14z@j0&<_?|kR)G3;A+>V%ekngD#_ zysx4&N6l6{(?i`BTL2VW*^s`dx(~A|5FR@Q$nsyZ>93 zz-$^nJJn++fYo?3VFF|cHX}S6MYA$SP;ljSPHFn z`Cr;PT$z1F5(Q)Hj8}7vrBYDV8y~K`N$}$4*^Cl=IpgDi6)_~*uwcs5_-T9fRwc#9 z0VKK)4pEnPqHLgIccxX?shA-Th{Vt-N84;%C_VR-r^Z%q=}rW*Z#Rex<~QhGObz1< z_|M}6#{~m#@(|1s%ya#CC5}K&PwEo$W<^17v)@r>UnapQy9s&;auGI#ZAYZ;=OEuQ zsC{p|bVesaBGoNPrEbs{w;cTiuiBA|h}>X%e@SXHnJm~2%Qd&{BB{sZ_(XE3E-E!!jR%1} zAp=CNb)r(_iQYGnHl=p9CWT$%hY`*jkrgJ)Ntj-p)n0Xq8o8xhrLFXhj3lO1BCs)N4#bnC_Leh< zqgcD|{zA}aD+z<{oh>zQ_s*HOb()-yT!^;Gkr);;f8u=68P|SS0OB8hIf@ZXLkc4g zxTLjeVZ}!JQ*4VD0ROd0tO%d{@%Kgyts_>!vsDlvQV{5@8!b@Ml7mI!_vM7)+9tG8kBn`)Lk$;1}wvw zLREi1{~a*>h8(0@&Mt&F;to}d`GX~oEH-8iGsT~>0+A*83bToBbj{oyXIxm!IV z2UB`{7XEuDs^%c?D%DTd_^iPRv~3T&;Z}op3q?oLHg8|Uf3Yr-bauk9Is^g%;D`zi z4o>F2a11<-TDmz}7|H5AhqcKk@8*1XQCWU$T~|+uDEQaVq-w_$Xw^0^`TYXgw8op{ z_3ygF0E6w^+g0V`XZKcxSsyhyb}U?GUJ5eO!HZn>N%QZ4C7*oL9M+HjI&&9snN6NI zgMw^5dN`WZ+*d#_8kdu$^iz)y%dCwKmD$$!NowHx7kgZFDT;QG%+cE&3@(qFq z5AFu-JEy;#Bs@&JSU7YH!%7vVKZfJtd=uWGWgB0;+~xOS(TVpy9Pyg{L(?J5{@DBl zfkP-;%!85SD>ByZgMEuyn-dm@%g2A*j$&9R#h$PRj2^T6ap)-`SMW9KGE=o-4TMs$ zS&LH0$rScliJ?A-(qEeCJx!~Xw#b0fVBy+}M9=N%* zQNS<7im&TeM<%zF;@`w(HJ8sWN*dbq;afrEEB%X!v$D%BBGOzXLbLfjI4s7kn37*B z#`)Wugi(ZqZK?sGxJ_~`BwzlEq0KA~*R`|JmtFDrdzy6e%P}Ra69mfl$!VFhn`TTC z_f@d1m*r3Wri;M-p=pOD*sW(a@k)mH8zYNtP6=5>^evAyc>;PCEejUT7 zQKbpkW1+mOvmDD8AB?3rTkq=PeL;oqt3^8wff~W0+hhZrr6kKHfx7NJj#aH5uMr?m zN2P#sC8dQ?$&|dQ@&d081*vHs0VsC5u9}s7bf6q3$eDI~&?(zR6pxBE`E_Z3djIAJ zf^k4+--EpB*+wBd*n0}D8mz4OGFBC0E`RS$@Fh!S+0eS9nbjKwAbt+B9j|D!W5Wd{ z7WzG&FX99bdUeOc85bQLaF=$x%@<&uiDhF7q;8&CTDIt&%MrlCz$I1CSbzNO`g*aF z%3CkyIItfJ`1+lta6z!`mP*|J4I3NVK#;})VOYy>Ja^@7p13m z9$A|9OObvlFO45S zUGrcOK7*ee*vrqm1JSDt$?v8HRrxq=Od8kiz0(_Pt zb>i#D1a3K5udte8Ay#^eiOa&OMi6q4&|(JP!B# z>quLDH3%$glbR@*xZ%hQ;#HRmwT40WJ5wV+QwA&5I}f*VO*qM1fZV+~V(z#6wwsr| z(TwI+{3VSr0{2(Z8kmR|*P?O0*G+z1R+g3wx2N_J?F0~pMrfl6luF!rTDgo$~^#wvy?b?KZpFJbrO;;q2@T%uC(|%jF6C-Z?ed%Eav_w`&;NKpuLI6j^3n)_AC~I@3_s=q6(#I67A28!q=GRZXxQC1;o0QI8J!q9o1WsSCDxNa8%PVGtg{h^E-vJsXAchbipA=}Y=PJACWasN9Wqn1!P+APxL8=6!#;OU7&Y&#je59wX4SMi=e1nEc&kN|kJO zG>?lCH_&t5A1fRpQzgBNhrw_`Geg?w5YoMVw+=*DV<1 z`?0-N2oX6X7p+0DAnm~rT9O;5$+lBy=r|d&(O4Jve9pyL%_Rb~#8Rxwj)0_p6xj zp4IO$@gW4B_SvTo9VSM>4uIH~Ny6_PuDkR?X|(es0aCuxn|pGc!WT`{%D&$PefvEGzp_{vCF@m`4!qI3qEO? zNfnK3HUky{3h$hVkAEDv}liJ=-H4X!Sc zTSvgE#DLTQBR>S;Z1wZFjcZxG-kMLYKj@)sh)O$SIhrn3D=jV&{NH6x> zq1V-gbFaFVAD?fKKU>0xl+>K&Ml28MNb`tM^nWdvT3jK12#aQzsUaxJhfLQtGOGq@}y`@H)yUYuPn#f;lrf|UKaqa&Ed=s96NNMqdO^Fh=Dj`ei@P(`K!hSr~{ z$e@2)T*mtENGRcP6Fl!DqKh&seQDBj#Zd4}rrl^JJqB#*pp{jHybabb%I?p3-Sufx3|6Q@*Eb# zdca!Mu6V43;LW=7D*c|8?>G4Jq#KVEXawR|b^H6SBS{okFTz1ysw><83mc zmGt+Rfz9Y#jzYjy3)Lu2Dl5pkN+`zY{OhGretB8Yr9w_wRZ60dK#-dhU@YW22Y&gR@GxDkK^JZ!>X#C$XDE-714XS&)|V==(Z` z(r~Iu!5c~`3cibi1a#WZ+NIzKSPfiIWcSyaFNOXRhqlqLEm&KbJq)bf(t=5wFh4lW zLjubw4tnb1Ap+_B2new80?>--Q2)eW0l2@C1_M5l3Zx@YG9hoi9-yap%?7aP-70s; z50PK0bmz{Z)0U7D_OWTV3nKxt_)zfUE!Aa7f<4*}wLj`__Ez zDWt>a#@p!}@pN|{8BKPvKYysXWK3Ypq~rN>lYAb3w%~2$Q)ltjj+MAhXGWrqObW&8 z%!-HDG+w6eFjldKlRQ=84kD^6mCxaE9t;Q3uTM*oALUCUInUNF7awOhQzZ1RP2VQ! zx^13E95ci|L+^=C2g<@4tMqPrLvmw@C8uO;m121Yg4#W7Rv87 zER5<@v%VID(A!@flOz>2QC(b*T;v=+Y`?x#G(*jaGX3^>J+LjI4iSc zT~(?xVS*x69quc->n6%k(`=NWr4*}zr=71RPXDGR%+z(A4*ckl$NZe-dk-U~PQtf$ z_1NKsr264gXWn~OdmbcD=&=7XyVjHF$Ww711OR0kA0Ig#M{JfVu8OVcF`ZbLJ;w1| zZyMKtsq?R{-R}aWlJPOCo^&D!sH|dFj~11?8}pfeOy^4)Dh9xJLrfsZ!LZ=f`knM# z6F4E1djPe+e%jCZ@?+(sNImv@eFsz)RB~ldqMSWX3IGJ_jXk2*Fq{ZS{6YN0bC8#y zpbl{L(yao6cv3@g_8do8K;Epkj#&e$=`Daphc3nZ+$6!sQjx?nfc8Tle`Pvo72cqZ zj7f}yimJmUhl?bQi>_`#l3KY(t}L_oq|^WN7-5@T77+3<(vhT`;C(sQ>G_TNTu-)W zPzMw*3C??Zd&$1$>`(97d;g)x(?f7F7ympYv<&d98hi}BaV1&7Nel&q4i*d@+h5Zb z*8?GBkrl6jS49UijFW=&qBP+xqWOub=}z0gR5ppM+)N!C@J3WF`fN*@7fXri9WeR^ zVfIPhr3UC;FXIRg|B4o^5fBiO3kSAo@?yVJH+c8KjjUL-d_qh$V3Tdw2^U3*{#&l* zcEGTh6TXQ|dX@74e;edCLf8obKbzyg`T^JYi1%(INfCXa>P{@-0;j(T)btdMxZxXU z@I(YzDC&jkcKxfl%wmm+<h9p2zFj6Mi}w?FiLlumrU}V9LsM;w@9WGE|2HEI>b!-L0+JBAfuI`e)bK=>m1~i z>y@O2p+4h-0lfu>y!thEeEco)65NIH$Fr_I%D-TDnGuHG6lIF>g9lDeFPZchz}uCp zt3XYA36so3T-<+-9>_u5S3W)T@u@_Zdu2h?73ag;7aXqg!{JtGhVPKH-(K}uba{3n z2y|{USD_?dHWNsXBh_t`H;DDM1i5uU7L)nsf}_~e`>@Q?=>sxzh=J3m8HUc^-?W!^ zlG<6l&c9!4>RpZ8Ue%>bRJ1_-MN^Z7Xd#4Ii|+b%65In6Y(|-K6r_uExaB*erT3CM zjVad`+uR~t1KF4M$6*bq~~u?>UwHqQMCw?`4E<6d`B^aUNi z=)&(OMn$tV)jI&lnX8ACuDD+%D`>blBmf?8F|r}OydH5sFlsSK5YN3c0U*NZyFi3$#FekSPv^{v1hZe6bU`jAM`Db z4?8E~YKObYzDhUm9AeUM3WioUsVe>%?QAB zq8H}38F|Ny`V>bNQ&u+*A%!rZcuh90k?%A6QL`1N4hJATj*4H=IGxa4dVAg(mFL>i ztCop)!6dP{p}O1E_5@>~kzF3!dIZ1kVo7~i$)1FaaC!XbYKM1WOuRSI#rMz8kPTi+~;KgTO)~Iqfj3D3lc}tA5Kas1oI+xkJEW^pF1Pz(+AsO-d-NG*P*C=(}&WQ|z32@!u z-=wrZi3{Ks*#0ZLul7ZMD5 zslytK0`-OkdwzShfxa;(<~_CQwi)pB@q3y{$#pOp79m6*K1-1WT7%O>V{1?)rv!A{ zF`F5t`P&<_f6((T|2I6B%L>unpD%4GGC3%Kzk+mixale$;C0LYL)TeGMHO~^{|qhN zAR#3oh@^B3NJ&UZOG!7}$@x_Wu9(&r{O=u<}Ql2XlU?1pjK^k&TynX5Kw8=-e6kQ z|6W~FCi6nrVoq|`yzXV8rt#-vZ03iiJ(jyNDiub{jB=MOVdu;N#4|CBA@Ez$G7d+s zZq~xy3)H#R7Y&OnIuLG&+z!i13oOZ3CMgr$H?~b?Rjg6(mQ(|tB5Sr0qEu`un7LnB zQd34cFAj?HG+;eelU;M1~8KeAM>-`#HJpy|8;BKKK z4SjjQdgkNw7yv71i=Z+vKx5>9gUN5*RRJvKJw#gV5c4-TUv}!FSJG?ckh}R;Q6`&g|F%!ZaqKwdiiq+ba7` zmmxq@b0AdfQV^OD*dBixVC$8&$Nuy5qoilz31|H9h@}8qv^cS#arv456G9NPxdIEsUq3s@ z-q3v%>+~u2Ddj?k(PhQwe)MP;w;8RtbjnolRuQX3kOJyg9sT-p-s0_NqZ4ln_3yJi zhK8&?K_?2_@w776p)WpjGmEX_YH8{C_xr)8ZM11tCNeV2>viZh?|#iHR*mS(IoeuP zOh%8ZXI#V*FJ|&Fs0s}=%@seFaC*oB3X8#R9`U|d>hOg9Wx~@P;s}xNAhBrf_UYM7c&vNF#4{u8LgVZ^T1M#M^WFfxytU! z8Vj`XbMT?u$TU^5)RxR8O%vXjgVfrCMw*_P8f!hNne~;EN|v;PXMg2aBmXbmlUq*6 zk7;IRGUSn^|-ZeA{}yQ<5#YP|gTY*L$lQACU{L__HmvD=OhX7e3>75fibeIwOS2K@xIT0h}KV3G@qI#yMntygZBEN5xFvia-}GI)}@1WJC=fGeIwMS zp8R}J--8&!gUz-pa823;Y%MKD;GSD;F>5a2Mu(?OPC|&&z_t>a%-%Miz~53lraV^v z>}4AvJ;&b(Wd6}Z+|+JzOC*uh=p@QY7&WrXn1Nv;a<*uA{sP%*b7G@WPO}`S|5w84 ziO+eE>G0VUk<`_)-E6^q;L?M%F^&hE26Y#5R883ek(S+gA^X?wq;^R3(jWnu=KPP} zRBi1Ho_;(My*m&Pdax6!PC-43$J1?gVd~zkrEB|Pt1Gy8+wJ5qiTJ1Ril!MCX%4oB zdo~l)?w&=u)ApMwan0I=WI)l|WYAFNGn?_hFwdO04o)u7tM@N}zfTw*S8YWc>+W63 z)O~;W(dM4wM!@Z`88MPUpru-=f;U{LXYA{X!zF|`7r_hlSh?nFPz2?|R1Qq*BMoAB z@tIxJ=yj4J(ONqtAf*?K{aFBC)h0Al%KxS6JF{HmMC`n14uLn5geG5JxdB>!f=%NZ z_M_AqcuYo=g~FUxZVN1ZY}xd%C-(JktU%K1{;0kx87o2sI*MczSUg9O;WFkHQGLRX~?sAOb@K8@5a@J!uIC%+vlIix(vAS>|73{@d{ z0^q+;G-vpJ5%wJm{0u~zrw+;t&IH4CY$WV|Oebw5KYGi?&1{V(k<~mmrO+5e$Ie{x zz8Sr=-?HcVcCK-GZ+stlC`r595P?JNVvq>RfB;B)QR}bFXF_gNGPc|hfTTh5AyWAd zcN|Je<|ndi_U5o(AJMpsm1l2c_6p^P6o(W0xcoY4F8br+CTWSh_%lo|+9}YIc@dj{ z(er^>oqyLh|IgX{uDUcPjOzDhmtDE+i~);rjp7pfAJE@fc-A1SWwjA`l=pRQ$r=a! zm9Cp@(I;KqoqSWAMhe zepfRcbrV$OImPw;IqpCE-!3l*lzMx3;k&xpLQQiZ zzdF1#o-yvMcM?XRim3DTjZV-Hgs)0M>}e>}@K_?)Y{JJ?x@X#4?yK_WSVvZLbhK4% z)F#ZyNzCK%D*qZCa->QPOaCNW!cK{20e)kV5l8oc}MHs6UCF^J0) zh-Fjlc5RghUT|rLsu!|626YHLz_};g5&N4;WHx%g*0gCgyF`()5R!YZGp*q+Jrv+W0d;8I3UP5>fp*8mY0L~;ov=8NTJk2{@o`=2*6K*oSw{`B9ofMDG`5?kLsSH@UgBTtXS|a} z{H!8qi^wqkF(1nFf~h6=`#fID0^5_=)r+&4f>R^@3W@Bz9Gx!Ywq4!uAGyy}#@)@_ zU~H~|OG4&CpoB8wQ5g8y%dCmgxwuDTE_+Nafn$-g-;?u@sXm}GOAxyGBggzUwGAUR zzsw`UcbMO8O$tD>{LIYEi0R!ruc)C;i`Cx^>*PZmPXE+PK52F5?B$}uE((*?{9l>X z`gWa9ZzMO^=;_1?R{xmNU!a~9!^!T0FN4U1tYk0hoY#bdnEnNG!dC9YOu#5tKkQJP#iLRri6|4}oVq1^YZst8P~BJtu$5Hb3~ud^H55 zg;{3cLzZ#m0`P3rJdu5qdy_twaWorE6zpty_3s||1`DzE!b$qwxT{hz> z{ZZWG&ZEyvK# zV*XXq3`a}^kSf6XNhcsxM->lkNh>NUVi|;QS;Hm0-o=;^xLc6ULrDRQ&nDVdQV#eab%+xg0rY zJ!UBQN;h-9bQt(v&7cd8Wxx8jhA^e~efJ~4dGUrIL_EZ9alcO%BN@M^mtUQnmf#Kb zdm<8ws05(){gJIpcF(ufkVm-O!x#X65@$4#-tM){)k|mpIi9-CgmuDC|B|V}Sedu~c|DZ5{!t>_D<@dFoLA8ul~` z!$#7DZvp{YJ=e5RaLl(90ve{f)=qa$C*SG%k+%5Nh!+S@kQ))tn)9D_KU-FeGxoIa_DNR#GOUytITecLE`v!@0vAY)O$=cms)ApGxANm;GlYVW0gR$`zk2#Wx)=KrfW&)wMG83g*CP+(| zDtJIDM_Qq3V_sco=%_I?iAMUpDgW9E&y$P4bGs?6kxYjOYL+saf%2u__nYt2Pwy}I zNlACH`Ok$kRO#hBB;NZkOdB7GbD>+1F{xScgmGJb+WLI}mIXJ}`j-_^NuPHU&(vv! zrCfV9mQ8C3h^Rc2jPJA?$qbAzHGBQbY1D}N>A5)w8SC!CHJa}rl^VRCKOw|p3S8li z=sx6(%7M~o0@UH|4_6-3H{OsKDJ8E7)XD?V4)Yko+>vMG6=koQW#o_2ZJb?ZKU}TX zNQfFE{vk$c7KEM4kL-_4u$)yMWRM*Y+?Kw^!~@hKwh(A3T*)mby6@=Tiw#uiRJmU0 z7B|OrPE3H%OBOp=Ob8;C_sfsw-Q>f?NNwO5NA7SznelXE;Ma#QQh0)oTwX>vO z5-bT7;})s-as0ZEJa4v(mt*&c_AA=)#OrlbqLvDSiwAC5@XvQC z+(RC7EYUFo3$5*xf7y)bHHu!M%>?ksUGT$~3*I5AwN+H}<8R_u?Nou7$_b}*hGo|{ zpTb=VJUlSWSvPgWdftaCT;1QmU|U-aXi2Akhcl?>L#|hhI?{zWyo?*bWdncQ8~+64 z@1diNlDYPdtZKfQqE6CCuzc~z;G5yuR-){iEJ1b&iMFuMldOyPA63lXWGUiCBXg>inl&+ET#2P{SHZB-rWGFYw!+#!*s2TpnO%WoYuZZ!KMK z?sw})@%|ociT^EX7Rp&#>-DrFx5eDReY1~nO?9~1P5qfcSgBZycN>Kr7xODuGPzUK z1iEl?+FnfaXN$h4H#zvEm2U<$Qcnv?n=CPCsmQp$!}hG*w(Y#0pI@&@v!;98Bl-#7 z&kH=4`Q`A=#0LDBg0@h{#MnnN;LdrGxbwNPPw#siph<~p_9(~nKH-Th88tQamYhTI zHNvYXp(JZkNYNaRUevzoqWK}-syH4+QQLu6VEk^IvFDIP1f&qN4OGl3;Pi#QrUL0G z12&8=L28S8TokqBxo}zUzbIl3j7fyKKu^Gk?1I9-FX$(XSMCG7qWjQ{glO5{@0bA@ zSJ=rIieZn)+MNHZ1xVhMybs{A)k_CRf%jOUv8Z;fVf1n3k5SBGch1?;`-@UN7>UbU zBA26g6>PQJ`I<5|_6waQ@!ts+ubmO+$4e}UYd&~A$#?TkZf+!g4g>vq?{Zc>m5x1+ z=Tw7ef!7$!kpK=6ov`}`7}(t0L=VAUIJ&Awn*YXq6{WDdbE4zl-A4?@2dOmSI5sU? z@T(kRRxLHejH0c-vDaj7>nNCHHlI3SH15N&gSJ`WuL`o=LYou!b+TrzoR<*`k}Pt~7Q zsrh2gV&F7U7SjTXN`eY)q}$4t*y!ho1ic?)I0SZR!vn!6xjfbsn36iV-kS+{w?HGj z0Pi(J@GX{$sjKvky2xzjp(4y3Y3K;)qSQCi#{y#^5X}HF2HgyzhyAgWe2vJd1)K0N*ONYtz4SMJ9uGF7 z$%;FSzuI&YL)ny2k_+8mwm2I%=6szNoPT?Bu`gn1Sd3TSB+%X1cki~f>mKWu{-{46a9*I8FPniSgP)9`80)B(-Y z9*U>Ghr=H(XEnQ#cSq4oA+!t($5Iomq~HaVS|Ec+ZX~da`0E9@AI-koy3CDH4$+W& z3iQTzWs=WpPe8oS4t_?q!kD-Y7RNoR(eC0vzvx5>d%rO(c?&hM3gae(+%*ROYm|0k zE(1yy)lunIu;QW=ZJD>|TWtP9Erd6oBafffDo85mmFOe^nMPkc`FN%I8x6H)23gbh z$E9^L_8se-p39dJA%mZ`U|;ALA95u_-fOu(An4dW75Cs#@y_T%E(c!Yq%Sq_L0!5Z zJ{%7`14^QZ9&va1i1C$Ii<*8Yl6mD*ni6M}bL8cLf0o<@o(#-*ClnbGId^XCME7Z;Rdx6q*IISzg|13i z+~#WpF_8wI3Y4es5Ig;66gf`c0v)caNfyg6ONX1ooEqXVf@7ik z@csArnS8Fd>(S+svNz|oLypiJ$HTz!P!ij*DT>a3&VOUILj#6MaNikCleLiDBPPz^ z+v_EfHo6ja`GrY;3iA~g`!!UNgH<*>=C|Fo^Qsu^V<#sKZ{FI~0^eT|X4{ABL8iug z1ZcjHN}K9Yvuk{WJs!&^d9+%O9Z8J+l{4aat@D21BL%uCKtfD>eQ|--A}*uj<_5M- zqF4&1dsgS0waLSSVco|UjmgmL;*F(lYaWp_1B;k&C>hey(n?BBCa0zrL91B=;j-Lw zD1+Kfs7Ha(uOKlEV49WX=>m~dhjQbhGjcXJy_oNCPqL!ya4)6Ljh^`Gj?G@ZCT4i$ z$NFX6hLo4-L!Bf=6#1B+hPoBe%tX}tUJS}|^I!+7!^zy46-VJuls@{#3Sa3%T5j%- z2nHq)Jn4lN@fVK|LI0QZYxrPkR2RUxJfWx*jCHW%C5&r*3%r=4JdQ=Ngk=n(eo55m zB(VIQYdSjDCgNiNvw>$Gf$qJ=ZJ{Y&Sr`;Z4X%F2d&y10A?)A(QYM4^6NOM2@;H;2 zPgCt!V{{xx{CRiF&y^-g`*6gn^$Ka-jb+maoKwC@; zer^Wl`e6*XRA}Dq?sSs`meiCki{zW#IMjdnJelm-se%P$Ka79XMOV_bF)A=uh=M#O z8}C`0YTv;FHW3=Qs7bC`;M9^4#wh7MR+uh9OxobneX~3kyoc7;fV{PGWY`MwB?K2T zFfY4hCEc6-PZJXF@9`^5%nDi#rU#uOsi8M+!LT1jQ|uz1oB%lX4dmfh^pQ{gL^IS6 z>!k|>c4?4*ysgLN@j-!NPT~a~5Vve<{0`rVezCQQ8t73!Xix8M2)Zx&s2asi92$D#vSu|>>X7I~qQ7G6Mc_cOQkg~#zLB{hY4sf~tsFNu zqw4l?G!X^luaPfdA&7ZcM(if~^c7=g=2z;(JR_RG)H!$4bOO6MV7e-Y(a-BgiWXDMBHrA?QJ%8Y_}RxQde_x!S?U@;0*@G&W9 z{OAZd#2j~})EyRW*;x95c4MNB*5PyCwfi<+PiY?07d5p<3*Y=p+-(=d%J<#X zdA{k)!Y1Q-$W5>E#QVA?OK#q+j2008P@}PntLy1EqXsmtdZ|o}CSmJI$n7S2SGg_K z_P(zZdkf-f0z4D}@34Lr@{K|a=4MrFczDK~A4|_@3MT;p0h%`{>F55FuFt8%yBGW< zE>LGeGqO!jeM{|;g!T;+RXZzp@Ilv6bd5EiS)kR_1LNZLv@wi=mruU0^=t;f0hgsK z3E2vKTlVv}BSx4gN>P;XN(Jvc%%%&LYgOWLiYu>8HZ45T8p9$L;F<4MKrQWSJBc_8 zXHSsBaY0!NrSJ4o2`RA?VWEb8uydJKYV;&B&D4*gxrHF3f z+cs7PXcQTl${t8nZis}w)nnZDqZI`-RK*Mcst+3aynD|J7%`M`-(#US)6Nqkw1Gj; zJ)JP-4H<~5B2NMN?1xy62K4Jk=sRpJCM!_#Z9y1rOohraPd|8OHo0mlaSq;}f08i@ zcbPIga86(Z&H5|+C{}qP44(Vl7pj_Z^J(z+;M0Kf3*LpU^MeI7X%698s4c23NLf3> zL8vpmD@1yIWJ692wt&gmE%9_Znn$d4Cy#_?!fEZpL6VjL>@svVD#GCc#aPDO_QS2e z+)cB~9*GFwBy%+O+T5u7_JzVcZ+>|-Grw_XmVGLh&-m^g1Zc%I96waN5FAJN!bEe|M`ovA;*n5m9+g93<>EyGh9Qm5BxFA$NfaavI}l z5696oS(5zYj`&I<8*rz12T%T`jjn%A7pZkwp(IOE64{TIT6ko0#Nk7MPG-l)JBXX~ zi%-E`sy8m4U8uv$h>Wd2gq#^NLKkY6fsSi)wkmMsR-$>XalP}r?$53EsA(99nZVV@ z4_1SFB=6+v+>hJJbSawLw{Gj+!QP-gO;3M)7OlBvFLBl+{(V(#CdB;W*Gv{n2?FnS zZOeVgxuJihtl7#ZPb?4hYkVT!x|ksZfgcVCeL&g4#YS`4LJI>&c60%b!z>(AW>wp1365< z`Ng2K{dTjxdo>+-Ou}fx^|`a)w76_BQHonW8f!N9I;}NyVnTK`xZrVYs6Bf6c&xw} z{0pbJ=1Yyh{i5j8*1i1CY|0p!FP#?9cZ7EVM8r9d-2lr&y^ zwCmprdnW@Xt!xOQFOq=7Sn?@8sBIC&=FI}l&kNK(t2SSFe<9nvW)+9ny|w6ilanK% z&!}>rI2!8EPbi#OU~poT#6un(}5U@G*S%ng;Er;y5*o~0&C;G*I0oTCU!7g+s?2+y_ zWPPcD)xFbAuS(IP^p6gZ~)&&_J>k3wr@Dy*017ZV^4XLbgr zJ~!VQ8Ed4PMC{f|?9w{#3GX|qR|hPZFv^6cxUqpaUe|z&Ra}GPN9ONJF~QfFM&$+i zjut}`pEfsnV19R+CVNPWWMUwTjk}BA=^Y?s`;$(s8o5w_a@*PI&OCW>Jo!Y@b0JO# zQ;5UP?S8vCQMTGh*fq8Fpmnd=8aeD1(pABl0u(KoU&*#y9gcfHx0vs|8pv@;IW-Jg zF~EOmaaY>+g~u)Av{l3W;g>alN0~8|ulE_0E8?WH8*hL*JG-goEyy_Lh{jUZ;O*sX zziFJ&?JtlzYss!ZDtLexB>V#jeM$FrX}@meLEy_Sz#u}p1x+`oD#btfiA#zDWhtM`@(id9eM}+L5_Bnz+#M2; zx-Xyd=)N0~UetJlYpX8(dc_}(soC)m|M((y&@S9(Zo!8RUM8+Q7%MHeq0jqpFUxdi z+V%zh5R(5cgG+YH3|ePM*v!f-By`cf{@`k4^q2-Ndw<+8p3aLN_4vW zw%SnZdI)w?-6CObR)4U=e(h(WvNmdEn@`BP9N!y|CBW)6Sg10DlB*yWEsR<_z@vUXJzr_(a^-pJ2YQg<{6oI5KkE<~F9il*9$U-BQ9!pCFw)HUzq=2;9 z<&z;{)#gJEjA?Nh{(Sa!o_G#}2cg9m zUH;b;vVP~^vjqmHI%fC}RxNfSAY)x~|VxoT@$Ixebwv1ra8fT#bm(S)B~#MR*QLCU5m}GuELy>qs=wjjk9XVf9HpXBOQH|HQ-!wC8vc`VO&UE z@rWIhxRv8%O2N19@%i2}t-3;Mw|*M4-mgq#%-nLlw<75af*_vvXl+#>O30;;gu|NL zz`uYGRvP3b?8ET3+S|~1u0YliPhX_b1YJ{DUf5)k4D^y%FCh{4wta+b3^2D2`4Ah*P1Mhr+{uwF|5b@X^$#HFa#>qKc|4obQGG`rO zJNrfB@#DuGq+p+0iZU$qzlVZ*(VX}j=NRtP7-D8yYe>=QS4c=>l9|rk<&9u|K)LPc z!nL$1A=viKZsUjF;!wVt+h2;yHAu52FW;wxoz7mpzPo9`>^X*vT-?Og$MJ7p4q4oC zYH-1OJC2_N{n4`LHW$ONmoBh+`L4!yvxj7n^Rv}I4pXxYuDd$eI=tPmn2p3A@31{2 zhk<$M6b_dQvBPO59|td5qk3HM@scJw{@yJl^c^z;!i(ES#=W)g0Ov(VI@j4*A>i2F znNiBIV~S=!gcm!q1pCb!G4nEJI$B@c3cjDR`*jTH@C2*!>JKtH`k#dRJRrttx)C(M z#fwZ+(&xp=RL>zFw);)VK;#*3Nm;ISZ1x-smMiwg>N`OgPA4EIjw=ke4T(*kMh_Xl!T8Vx8-a3@V7u-G!j^|1+9Kd5wZT)H;%)n-pu11WS_094Uk%mJ+?~E-!#1cg_2oayEgZ^ILP=-GL$dtG7i5EXYu!4OY$wZ>vTs1 z{k~ZfIgK60W_*&GB4o3<%JZb7!3tf3bT05UKG+wasA-qxxfgRAt)7N3dyLF-8$3d4 z7E$THyp+OcwkpKKvQHzK?2zuME`a<-YPrbO#=LItFeOKaMdrsyA0ag`p7tPrmzFXNbnZ>z7z zyRPG7?MQAwk@p_SHS5bzzDewcgzq%00_-D%2pR5P=2@RDo z2Hk<>3L85J3xevq;7mpn)BDU@!30Y@3r*}wEJ%a%y~76|)h!>SF;P3RmY4(P3-bH8a8 z-SGPVG+uv+-2K$M`Yfl3MTlnNAL?>Pc|G^$qLuw@o9pNfQKr03Vq?w^(c%9{4!spb z#CUrRB`fnjy*(c;V2G=R+bb_Rq|Aa0HJl9Q3Y~lTvpgKK1{Du>*Mh$A&Xb?uaTJ*77`Q$2Hw|cW->iOdxC`n+1KTQdz@kYhsMinzIB@I) z;I02mjGaX)Jne-2(qMru?W}6;zrqq~P#w~cxj>e;*IaOB>uVV@s7NLtm$?ZU`0b5z z9d!bdV2MwPWC^euXK25l3s|<00Ne3nEmb#90QY{hBjFGEg50W2yMlmx9?8e(#E(9} zIcq&@4-YA+A_(09PX-~Up^;*0b0B@QR^!K5*A(hs-(dsH)nSlIEN1N`SkukcO5iJ8 z)$mu$kr5luK}p0P#AsNw-!s2i<~uc^#NomzCIidLO^pZ2^}AT!3L&td={JLJe7X0F z%?*2LaDbGJ&9wZ)h3t?gm!A^$B6v4V`+{TVe#N&1)cQWM6J?0_Q`j&}NbF{Ges7Qy z4SD$V=-|Wd^6loVX5#HkseH53Z!2^;;5-eL{aIt9vg0buIzM1OjU+FBv^>#)`7V$F=mbA> zOJu^l1#z(MqMj2x^;|NPTXM z=r6#fei*iIeqcg#5~?o8n5HH;0340h{l*@~sm@~_)aaZuuN5M4XZJ)icq8XJcegA--p?a_aeRcUmKftC+ZQ1a$5ftMc+P z(yhsuJI;#SLT;}9!ers&t%?%%7q~Y;Tc`2m4^z6n`64mQ&3lok4$BYQW6G%8pDD>v znSacH$Jx6VaAETD^>jsz+4pfTMMS=ol{Gar2@HkYudFZ3&)eA8NF#5z(EWwB>WesO zmZz;_gW=&ypg$}?-*!u+3DrO(^TSrooZbq$b(x&{z;j80j@qy+ZibR+Cd)=hMJ;2Wwq@>YFu0K&0ElG7vm<%6@G1iE~-jf+1 z*P+k&CgI(NawDMIL4t8$QVK3HoW)g$k(P#tuVcbUQoh5C7?lm*^}g~9CVakMO{M~a zb!lBpTRb_Y1J!`RVH5C_Hvm|r@)0{oOG~U-EaKdZ`ZQ(;4V;>J(|U|6OMWj5u?6l; z+A0JtivvR%VKj*kXOp5-re!Jp@v372hMm4r2JtG zKZUh~y?a-EpFf8=xX3SA4|g;Q&>3TF@8Yqd!o`k?-(H+oO_FjG9G)$ zwdtPcxj7Kuqq6?s7@943A3X{Y+r6M1-@DayY2Mv#Gf7GWJlfv2KVf=+F*1Sp>!T8$ zb#GiNS0m21f6RngtG~N!H@B7gH=-*W!V@t;*3fMs<|6eRdiKkGpfP+&u8>JAfPuaSmduA2pHTzH2B1>dzT|Sjp~cpuXZ*T(R5sV#r0(S$FrtEChmjl&vrLkQ|7-=TMdefaQ$? znz)Y-XIDfg=3;p_*w&L66rx11gp8DNoRv4U5mg!ib zeh88sZNxu4Jj4Lw9ULEHkrLu4E*H23-EKy|*7V%XvTLg@&fx+F1l*y^a%LfLH{erj zY(4}Df6ZCY2hC*(XKFvElVy?krQoz1_GpJ@?Y@&Q=);?_@`^$LU0x3yh#?COrow+< zWP;qDZtIqxo%pT?1oxFbiy)O3PG&Ino?olm;(T)O+R9cmaGb(>91DyF5WtE{;;o*O z@_+ri8VY}fu|QfiO2TnY?*o^9$L1aKV!k3iN zj?)6ufQ-2z_{~+j93%!~X`-O~4;&`eaUF7wSNf+b$q(;QPwj?9jU!m%bNek5&_tkA z%CpH1oI%dHu?pR3#S-*@?jKjpZ0{@|mh~Q>WD$!G$H_S@W)FQS25D`Ls5-{P;FGpR zO~~<}$uQ#w4PF<+yYFftIX7PoATk#gHblWOY^@JpuGCx&|EZk0nLQXO4)xj<&=%s# z-2S4v5njD4U!RgK&UZ$yNVUKS|A1-oAk{As$vq{YZz7R%+rLUyTADFAzF-8!B<9Wx zr&=*~s$m4Aw1M9Q&=s;;zh`!c`;3@v*#qr^(6F$uK5#USEn_HKPZ4VxxGS3}lBnj6|Fr5!@yevfCOjtQnh`VrMOe^yz1ZGfg!y!c z5lYr`ccQd>bbOp*1vehUuM>#b$F^u!B>21DKZA*l%|~07?(j(^oknWj={D$Lz*}c? z01HHg)@}ErOvP}nFn(425SyGt#p1mF_~+ZtlN3sn&?${ozs)gciVvKNjt?t_CXL+% zm-#lIACHtk{+yCD_UKJG(3PP6(pzgyPOA{2goV|Aqw|nodS`<~rTL>-ZluhDsB`7W z?&B{FolGcaKlZz7I*{C|I4U~jB2W_b+1djDe7wMSz*ll~9v|8N>f49ed%mvb)@o@S zEVVb%Hwn?ydHKN#!djL+y`q2X3;ryehv1Zm)st(peN<+#>R4J+8;r#78Apk$F`?m1 zGqZjxSU*N&H?%-87lKN>5D|yU_r75Q_^e?akI0UvbP}o&PS>a zKg#Mhf15{$1d}_ty_QfWDYereG1*S|uNFX>2bInAWp5W|-0d-!+O_zDJ6Efg5rh{y z*tsA3_0UP}ex{`+gAn_n%<>7gJ>L8_wi=u!N@LRI>Cf%*ZIsF;4VRL_p5lOmW$x0j z=B||LE~<}M>mMZNgrYPPkhI?DK>8_wr6NJbf<5B0(6X9Nj%I8)?1Zal?9;(4j{!%+ zj%FsxGloCZV1h()VT=3L_bM6uH=K;`J|kRtQiQ@o3#f&6qvQNTeB(3OyS?+$z@QSh zyYcfJ;=s+gj|7mL#ZuG$1U36e^M~#o^OK{m`w+ai%$wDtgrKZ#Z!EzR--8QXG=S{M z{MV@)4r5(K(7?xSrzDc*SU}1l4;epf!h|xpUq|n-%K?@s!2aj;kWITpzYV)+{27x! z6CO5Dr&4vmpEmZy=*n_jlJCW;S;J`_WDRwFXB8Na&nfXEnqg7I zsc^n*FgRGzm4P=DT*}P|)~#?tjwCH0Dd&C9(G}2p?jkR zDJc%eI*S0*zBG^u(78bUu$PUjZwu4~`@ID^fY5u>F<;0>@+lBG=6)fgTlCuQiqMQL z!*cJ$yR+SE^V9yA3w$?POezd9?ppN*2dkaSR)TNKc>?2&PU4oRL{fe%LDlYnSs{{# z06X24uocL1w82+*Rx7kwPz5S#I<<>VQfRC-^_X5vKI)|Skzu_hTMh7|UGtV-B7habiUTLvD8|H8lg|tlyW0G?X-YJ} zaPkiyx(1Z%_HkEP<2L{T(+kNSX$3ZgC;UMJ6A0LmlX^alc83%iJUf?IbdQf?aQij}hIBlrgZ+ zj94A??_Uz7Uid5pfQ+b#+rePl`)YTfAso-66WX#aCmX%Uyg^G3>O)o-^8fJtve@1` zer@_W`|T6ZU&1~soor?q61vb8`S*pDR8*Ac>kZyhKCF#(gEchAU|jbM_3Hipssact zo}exh{#cWcw{$QclDUX>P{)g|`Av%NF>Fd`HpzHHE*^sJoBvSqYSKzh)9s-oLaAa; zmVW3p%u-8avwB57%}S>|-^3F0D&1^K1F~*>l}#4BOkdk9HmB*SJoL-}%M} za|2g>@2?%HD1kW|8j^2ZP_QUQ=Ulk`1&Ur%)A&kW?>UAC?T-r@i6B^~j( zA~?0D`>AOpfUx9d1H17;X`~x5|K-y>e=Q%el(8I$7bzc0!xyp@FG|g8EbKT}ki&(GsJ~HqOM#%5^*7E-MP>9wpBv<@Uxk0c2@BPnv zSa9WTNp|%e9_GkKaqr>;qxY750WtKKH2pR5_~dSfh#JG8;Y-GXf25ksXy866El zCwD}HgM%r8Tzc`Gly|s?v9Tb+X)qKTgZIx6FaQBR0i0nckhLpG-~bshurW5@Kp6s> z%ntQ~f+?{{O%OHglN?N+xp1M@tX#Nw1K5GTLvGlNS#ijGs}?O;%seM)h0XY;HJRs- z7*rL{}nz3Z}Z_A(aVOgXAB|f892+h$Q5(y(&5jY;p=7Bl2!9sU&u}}pJnTW+A$b6vwIBb0E zZfx5Nz>6gL;fnF-SO4b2m-G||EDJqYb@x$aC%qMv%BZe2*f)AGCcTK`rcw5?At1^^IR2=U7^5Z;VX>SyglTV zF|+&VAdQJ_s=u)@7Z(=;%c0W|K`a6KgKJcRgByKTusbb-oTaQHw>=Kq9G3;0tJ73E zbV<+H-VAVRN&fj+DhCf3&?cl)`$mxw8_SfT-Eqv%7jlfi(s)w*p|>s z$urOv4_(=3`WLO2nH}W+Z+orwCRtxG^x02sV!Kbv1F(MA=~ueoB~`4y$MB~mEw7HE zEK}3cc6N7Pm^2@E-mC?pPb>uZ_&OS=g^YW8c`e0Gkxo*t#(zA!|8jo;)8ssm7UQ%^ z6*+MW@v-3qtiO=_s+$s!E0BTQMXA|4MgLw~xO`ZLtt~CL)yHd$Z3hNt@aFo!ruT&) zh7T8x7oGD()hQ=miULkcWS`tb+HVz`2RBPC+>MzX@mQ5W0!k{0td|YSW&Dk^_1fK# zukL-Sznh)y4u8q|0~IIHsa&}Fpg z?>8OT8fi)nm8qdLG!p3S@OW98VLEwzArH8nb z&`+521^EXea{dzG8KR)Lr59m)L^C*7|Ge7QjU{(@ z&r}LLeR|y)opv7UZ|6Zmd=|U6&8{1zcZ1HnQFCM=ZsGQ{m%9fQ9* z_;?4+5JJBj*9V-F*BN@*#jvc@hx4azc$W)-T#YzJ8`3bFO{|HDXXG1UN7=Ai-3_HGoj@${n2O--i3SMxNcUZk&XaY>|Z zUH94nVS5rvDR;F~-fg_<$$}?hmCt?GXrj#g>&@-7{TD;OOS+*90u4!C-0J)ihU}%( z%!i~;@bvD*?hQ#Hjh|{@0%HSjJkC>#e}^A`oyVL_d_x}*LZq7Y=>5sM&<`H3le7%k zhrZZNmDCgnpv&>5f>ubd`A~z6cNL4w^cf}P-J>6*046{6#tsT#)q9-u?cP%Nd1%Lm z7F-RSfQL4#JTv7BZWYVJP<&s&u0$RcCW0y#?p@g;P>taKY({POnj1H14^OT_LLn|L6G#M1##46H?(c!7?&u&kei^nF%u6(GZK}6LM6v(*Ne|MU7HqlM zVn;(gY%J^7dEH=N9~l7fN{jiEiZs@7r28MV!r2}Q>+JQGXsMryttrOF>7;}jr5j!O zzbIKW^M~v5A;if)VsLSf6!@;?{^P7+p|h3g9xdzuC@B;0|A(=+jA|?T_C$0k9g>^=&pCIzH|~35+?9OFha@{$ zd#*WuGH2`=!c;vaY^M=-e)X#-xd1j#zn zN+gsd{ao#J^3t~xhcJlUT`}c3*PuBv?Y|NK$@@s}2&5QbzlK&<@&SJ8h~6(eZOe$O zc^kU*m$~t^H8oO<<1SCY_npLvGxyWBNSU@u3V$&RADxBgkMDJ0%6+=~+zyEF;I#M! z(KE4w2wKgS-L>{Sh)O?=e|cR>ItApH_lK0)OWRuraN|2YGT`MZZ*hJ%+SUv|heZYl zJZQx&rzIvkO_sN2`u^V#%q0>4S^$&GJ2*iqQ%?z4j(K$vq{n4N^3^h!6d%gS*bd-g zCAgK%kqik=G}H}?#0-&fqMQ+D*aJL_Bdb?9D`JQdViX1$+vs=WdC(Ua^xA`BW%lX_ zGr}2&fjh`{>zMn2!eIj)v?lt6-U$mp-o)CN(U`a)I^_gKmAJ5r>{t|#0yxWdMpgYk z83!#RDl}<9FUrS9O+iFNq^Ys->R@()g`&@Z0`1q244P}x7XPPb-hkrV`u7WjO+SK9 z&ORuB3HEArfv3Li(B+GRhD;=v`(!`FBl+<PbZ|Bdx_7@!9VExRpfr(w!mqDLS_PulAD}^9b3gZ$%>U75LYQWQKN3U!f;zIa@!wH z4+g5rBk=*w6)qb;V;Xo6pVISppaq3m7~FU$dueV%mL=TlE(B! zBIU^OZ96W}Vkl@{)IE`yitfa??I5-jUK1Q!R0Y`55SDEK5t=P4f{lMc53(nQE8P4FvCRLx)JS3W=(xzUl+$IXNp0u3kwSFi6U z{`>)ZwaE}Kudgjg-IXDcTI98%@ga%g7s#M#a^a73`zspOyg2n_wsV(#^zi6UcSW=O z%dtX+S?Ll4@xp%|3Km30&@K}EO1fD;(v*j(E;KN^*X$bRm;JxQ_CWFm%Wni<^w$T- zQU*+M{yS=Wm{|xhAj<`~Gy*QpuJx<^=PZ}tx1@-9OFG*U+#8#vJqhvE%It7t)FyR9 z3G7nG0`vo!P_tkKX1iwpp5Z(S#bzn-?|R*Sic*6x$N81`a3v@B$F-xULEXY#u=5ec ze@KIrG$IkWh(@63s|#D+w{+9PzRJM9NR^C<{erez@URv-oWDm(&jf*y8g9LzC(dKY zze0$HUIZadOcX56Nf^zse;f51ApoGWqes9JG|K;e5Q3q0AU4I1vQ6`i;qS1Z88go` zE}I;m@%}U!aPFuM6TRQ%lRcY6esSb-LqSJjstdxaN0~v~Zr>XAaVy3e5q~jF8I9IC za`OuoIeO53?U+(NWwm%vHoT7~`k%WOA?s;p=N$>YNJBXM+TjmFd~=?!3klLL&t$({ zPKUzsS?S`QEmT4Ey^CbRyQql9pjHVLrxNI?S15LiUOB= zI838*|I-5fid4`LxP9vZ3(ghYh)SQ`1N+e0v1)JScqkDXMM8%ZAO6E90g_ z81$(b5MHMh4&E1%izeK?dCx&1pHp=u8MiZC02!pqpPu}FqhT94yIO9+j~A19V+3{{rwFOBS?lmbOf(Vq-3HkWp-*ds9lzg&Vn+M64Xl^D z`8;M*pH|XqT6$Aqxwid6XI#KTRhxvyy#o8|P|z=c4EWUH(KFJhA3b7js!EiypnohO zvVVvHnLYAO$&0jJpu&m`*$3KWN;TB6oC=_E*#~pTB#18eaCt$c}vK z{Knxif3I7{hRfv^O+G`swp7xUl)Ny=m~!Ny5Y$^&3c$(4O;0aa!d_LOiz5PW6wX+) z8>i{6_(#Z%Uesbw>vsBqTlBT}^xgN|f)6z7VINfG0@gzj8b02j*-%d*nrPLLc_v2a zO49n*$${cl{#aG(rj<3DcVFm$Grwny^`mHDi4s*(c2bkX_m5{ZHY0RSj<9>Q=N7`i z^KTd%`{%tr)H5}MQ>8Bk<3yuKz?Kk{#%zeDuSjf(fC zH-;&7j5+9z*v(|6OGB7-X9|)WSR9g#|llhGETa&xJsD}U`X(9+RRK*RQZ`q%CWc^X-u}HKd zfZ~by5FrgvV`LVJr6RSf6AttXt`fj~@=jI!){2$k`@gAe`!@s?``%_N9v1~-55T$@g zU*oWi$5qEr@3?gVCjj*^{ty98%yV4DMr zyuWWS9jvnobRdjcV5}szebs(a+3{HR?PwJ`wyCaQR6} zzN5H(d%pL>#rMre1Vh(t)uq(~s2=e5GWe})3spln_`6all=0(~DC~nd2IvK5jXkI+ zAW)LQ&bl$DR->cI`_DZKXq(%5ll2rovgo;6>^EEgWMgDHTiUri(81IdfSZyvSDTsc z3`EDVPYFa!jz<2QY7mqj{_VL5+^P+b$rCF7d-TO_>)_U;6y-+aBjdaFiZX6ZDdM53 z6x9~ZO6DXkV{F&91qxN=OO)tMpendM6e5z-6P3dfNdxogH}|H{sm~&jWr1YPa{{7l zpc7p`QNDo(s2K%-fc~* zVqZ)l`#7=59je0JMOXQEn?_47oEnJ<2eP>hIO#7R!esG6eFLtl^#!sY&s>Ah&%b`L z2_tPcLf8vJC#CYDQMv=(BIAw*U6eh*05_qRC%NaWZA<&9GKes%I`L`Fsz-%>;+Dq( zn7uL3{;dEw?hzWHMlHw*+K!Jp6Kp}B+`=F=K`mA6&Da+!$o`Z|PC{1tuk_OX3(n|5 zdH3d8a7%zHYmLk48WPzy9M6%?m5JE%vj6kY*1S)jHEvX4>0OHkoojZ@EvKVkA1g~q zsf%DX`GpT;H$D=;TlQ>3I@7x;Jr!1eI|QX?77}GyAmDnfRW<`ha+J(`BIkcz_Ac`< z!mEpm=CK@m|;3J}JQ5^{v)W$>k{E6ix2l8e@JoPzD$kFwKqIx#W1cx$d^@6!^? zKUeLAdiNoFWVPfU{Xxt&pi$K$rsHk!8EUE@XY)nq^ytiU+zeiQtC)d6|8LRT!?xBq zY!(_MAbzZ&4g{q?ICrRD*--SdOyABs#Nwc?tX#<-py&*Gr@njc2<7Y(>oa;zh*0l@eDUx7C&SXut0XJmB$*tLAuV}#v#S_=J1DdX`w?~UjHVvBzI9$yqDHi3st~$_n zjwCphb19h%<{(P<)tk)U3Vc9&BHweXHvs)#&8CwWotH|jp$&$gFR!m0MNe9I^zfZT zZx^m8o&cHNF0ah2Lx|cuL~@Yml)&1{lL5cK1>RGKXwflxHJracM;4e2YI4x4y$PpE$GVF>IPy_ZZj{$e`c@ugD%jr zSh2_*UR71Ku&`h>l<*IgC4fBGiiOi#9mAqG1%fzSirPlAy zRk<%3q`OpVKOK3Rp6ku0&}ol)+*2i#uPw-IHTbUxVb-Lr) zC$D%bT}_5TCwupF74wx??VIOZBgaKL-?9d(eu%YdqoDy#!Zmw0YX~ZJyESJ1lQZ3| z_+=*Lz{PG|Cs2HXeIMpmxXu0`v8V;})ebA6?Epx7&>NYF=KxiN&>Jw)TXxI_#G{@| zvwpQH8W5vk(l_eRPNac4(Ty1ld`%hxvGT7b6X>_AV<44%zb{FBZzV(hPK0!8AqUfX z_!uX-NL1!oheyKKR`+7-AMkuywyuAe!hf=-(N*SDRNQc0+`*x{HI0I;#LYsq34yLL zew_(NrPut6V~(w5BuXqP9k0{;8Vh#EzDe-s>;javl)07c3LG-Xhq+e#r^!$oKJ!7p zN#0_kcjjv5Y7@A}4s~?@qXh_Rq`ngHxS89l>&17;1zIu0WjK~k^634j;kX>Bdfy=Apu)4XVA_i49OQ$HAm)HbrMRW#smnXH@s7b>k)o< zwKZb+mi4vu!pz^lPM1>}dX8!;c&pO%&~C6BG3f~bHaUPn2-larn3pzNoNy^_?sQ(- zd{0hLao2Trr|$mbsaxHtAC8KrlM}2hGyHj2wCPj~~2W8_E|MBRK?i^6wa&}gz=fXo1Vt+=UKiG{$W+>D9vBfMeKb5}5 z-CY`)e_#~al2U`%O#{^NF7t0azwyY%AW-^$?D_NEa=E0GHi{%`L4A#zw&WgEf6Z_= z>CzKPRi0mgwXYKN53aH-x^?Njc#dXJqc|`(+mz;fT&g7*6TUq~yWPbs(IX$0W~8x& zX1rodva(@`L6I{ewKL6ntn|y`Zpb@55M5R-ddvqD(l*YCxO6C}L6OL4mPSX(IC|WR zqxwneDRWFoIMi%ArUe%p8}=WpeaG|H-U5^=Rn(c6kALV(I8QGt3JRs+8X{cHE2^84 zZd-)aD4ciDo84GzIF#q*;1Aa7FYL-U#YyNtX)0dnhpTb-wo`h4tx!Q~%zN~A^pZpZ zc-7*d-7W7bzC7HVs)$~GAh>ONd;i|&p*gG%Q+ur1f$If2>^EY@ZM5yPb6x6T`nc$Q z3ZkyHTJc)ti7{}~Y>&9({-HXr_#_tyj2!Mqwc7imk}7)FKsW62C6G>k|8I?e+E>(X zz(4;R7B{)Wn4@QBO~))Cac|@4wfuQ12F0MdA>W~=@iDW82X?~`d{hdPZW7{R5NbdN z>JaVZCZ~pT(c(;i6v4ytT)8de`N;o)H52-h#9<8Y{d9opau4_RPUheY-qH;8@E@GXS zS@IJ%x*WPtlSSa(z~(+S-Wym7mbgsub*I~$z3lBNb&F;RYIDZU^$2_knC(%?#JcCpjs zeXd7qzR^ONzvj(o=QWGNEr06$PEk(%zk(;Xt-(yJG&*4~)W`Qv$7D`8vU5}?l!^&g zKVB_@Sb`tMD+8sXWD+(c-)xkDsp9$bNKlQl>N}IIcx2d%aRp$pq8YM3wa{PT0TkGB zPglTX;(+OjN#e@ro|S9jjRMAQHq!n0;{mEV zfu0^Ox{+@C{{2+X^)th2=7I6Y@H=gf5+h~zkJ$fvAd$p=)ckY~5>k2V( zvr!x$6w+ebL zon2!{SxzBRmXc)V%Tw*h5SkrD?~*c% zV7quIF$VDR{i05hgW2E&^o1pOPbr|xLl0deMNKmNK?e|d4p_ZzdxJ}}aQib1IfZj6 zC7<+L6}iF94{b$6mFnmpc-g~8i88=v4v7_7*ILAD3Dwfz+{Mf#n;)ctxO zZ-k2k(_dm&mgFpmta+kEqQ03w-rb{MS*1>z^%M3c32au3|HS-RXn>JM{@J5P_mjbx zM8=E`-BIcPK#i<4>L%&#jAaX-;ludCEH+nWjB}f4;Q|3@uF`?3NPnrfD z0by;#Ld{Ez7kg|$8ug2{s%kw|C{Uu4EK1#myyx(|)oVaH~3^dp*!W4eZwm;o?_b8!e> z_Qc%7f904-EAivDpF~h6czU&>i=NaD$sW46E<-G8I~w)v-&omJvoYx%xcWlAMVeN~wB&0(k z`UZ06`;hC5M0lppM@4)mdB8TWLF5|nrmbJaB59tBx9E!e_@q}L#;TPhHrc#q6+SKu zFj{;$!Q0thkbW#3!_UmftUF{C_X@lLcCp*!-1OGs*6{Ll^8eJsN6Qv~;#iywdstH` z(|(D58yt+uU6`G9IHmGY{jCGu*(+3unbEAW64q@pI8s0`a_|bz{!XWv$hX|WsR%rf z)cjDVu=~hN3@cHc7}J;FT~{~|X#wIc5a-w+%_?zV)a#D_KaeLWI=DX~KoX=}oZLg0 zeIar^64p)0A3>OIno>YDCZIH-RPZ`koVb6|QHP0owGH_KzXaxL8x}%IJHg=%Sl^Gg zw+r-UQ-v*exQaD*GMwsXT}LZ7PqjcOPA=$nB(HzUy__G|Sr*Mue6F2vTt-f7pJ3R^ZhONM2W_&^Fs1(S6aft;0}M@=?==KSz)f14nAmy@^)`y5`bMPqL(aY3I61t>1RyHlVB1DJe3FIjk3Wj zY~yVipMW0L{?13*23%TbTuRE=GIqJ&myOY#oCY0J!yG9{ocRkD9^Ou1W@mN(VFeB% zH@2cuh;h-^)0W*Oar>W?$DO`_yC~@4W6D*sm;TH)@a}5#&`W&(94gLch;Nl)wf-Z^ zR`CDiJ~U4eBqZtS+4^IP>hH74TFS1K)8i314!;bK(Pl~?AQhqWi+z~|uSb`E2kXN- z)#!+2zc&<-QBRGO73BG&$QZR%` zn6U>;V^-gT>9syCKO;P0AhMhzGWVm6MgEXg?$}U2wEGBKj%T8F*o3q7QL_B(^ZJ@Q z>{1P=2aV|O_ohr#{(hCthg`=8c_- zgnIsA8X%y-@Ck^^#TYsLku?{0Oq`Wc-zVnBm&{R<6ytYrEn*5@_dZ6Q#zxKM)o-?Va80_{5t+X8-pSLMkZ^%BB{Va6LmBNk{hOm|Z0M>jrC$;utf+-t}TqJqJPV7uLnXWO1 z><#fxg$(qnet!R+w`Nj6nN4(TfuEJ7uq?mnMQoSfOGJf_T9eztRZZcCLGQm56ez4e z%D&T`5&h&?p(VvAkgz%T29SC2nI!z65eoxTdFNf>#IMZEG)s#3RG}!cJzKQVwC$;!$c4zD4Vp#x6!^q)k#MyWniW1M0(Ly^uFpU(- zuMVFN;e!{%pxRxSvQo$smwt)T2lL&pPSBadYIjBu%7)_is58#Zsz--Mr;=*{0J*bz zIwWR{&^T#*T0Cdq2rQ+XH3U*A$6`+gLtf`k|J8mYTkbI4IFSb*pLf*#Tu&U&C^U_X z_^Flhfy#ZOY@!^ql_Q@{{AgZo>_KR<)%9p9!0d;$JeHj30lz|MaR}(+4zKwDa&BS_ z%^w2(vEnWM6DFArc8_y9^AIjp&Vj*D92sE|k-7Of+{M=(H$`|HvJGX(^dcnv`R3*P zLU=^ekFxTlJ>jvTs}?4V^esFL8Wd#W*~;IRSMn6AB-50svkO%I!WpNrlyLDgEqxG* z_JD(UCmTNu>HEM65hRup6=MxTk@Ni}Oal@fL`bpuh*FwVqP|T)=}!l*kn+wfJL0Fe zxnP%n@c1KyL53;Eg|@;&xesUdCZ(U7cLVnDL zzRAl*GcC#26NNKn` z`z(7zd4iuQMy`YqRzQ?aC>c~BjxsJ_T1N=u(ZnT3L!Kx4YMS9{VfEN=eIq0Be`DS_ z1l7MfxH6;W!q6Yi;eYB(@j%y?#|7&=#g-{HN|EqcLqpg;5z{-nQw<;ikSD^A(qeN< zOVb6tK1vTSJ!9jKcF0~Y55BqXj00}zB+BUeNz+&15Ne)C(O^(^qnByscD0TKW$5UKr)M>mgj5r1f=ZzT!mQ(h-E{hDfwrB#dJF6%J@Kfvdj4`bcB3QJX>FX_|4nXrGfv zzb|&KiQ2SdEi_OsEy38W?VcvSJmx36vqSDfr)DeMQt9c+m$1j`YH%vKL#gC4gX;qGY znDv?ePUGkan&aXqYglq{@^Fp*pZFKBy1G|7(}vyCWFdQAU9Zq;po`CN`c49bzZOLT zk2LXrY!wZ=s@pKF?wJ2(XpfX({HZR;`0o9iV8Y?txlB*UT%m`jRW3j*$bd56h)H2c z=He>E1?9@@d#QhGqsA;;{AaZ&DLbV0DRl3PPZuGzi>%8**Y|C%@{&Y4x8hc-hXU&n~Em|M~#CHh2P$V2gXZT5+yB zJ9V-#nCTb#INt!wBb}3?-P#h-GQFZbvC6xWwhKd&@-$>cFaB`{hJoF*u$zS3$*&1m z5x!J!t8<8kFu&G0e(U-2v%H*>;&vKIVXwUowuZ8FkD1mKe~dbMIn1a<1?n1O%N-A% zog+3o;BWMhl&|a#jWG@HVb|nuVA5wN=TqW~P9_QI=0%p>y>DgMz6Aj=uczp$J3^+G zmv_BnwLhzVJ{e2JPY>LEY7K!@O()SQA*3Ui`N4}hGDCsIMrMBY3fa3?DZq>>!2fry+54O1j|g&^9Cm6y z>10eW^aVDz5+5mcJ^?jSK4F$ZKyH{7t~Jcq{l0F@=5p3E8c{g@T5ryF{*%++XC!oK z8OAgZ!1U@z$@d!XKlRT1VE&%d5~0@akehvBp8f z5y`C=;Ry)|wt_#*QkqbqEFfAh(?$Zn&ZZZ=UoB*SkEADkU}?2j<@Sf*9pfk2j;gxy zKQnY{tNCaQh)4?LKr}mdmySzPVM#e;&N` z#GRluSwqQ)ybpS&psyudIp|B2pfmxr%HKw)r*Ts^u|9N}>tsaj7VH=-K|$|f`Wmz| zdKLilcORvL%};=kH$L-Mw8*wu)DKs^Bq|@b5KBK=ox3N%z?tF;^h0u#kPala<6C-+ zClE3LV#UL^GrBbT$d!>5Ea=h%VD?YlKWvuaOi`eRX);De*WkctgbmJC%Y_!xl;6<) zHv>c&Y#RVzwig+x4Kex?aT9X?&LZW&zz==_JjDc{m^_YPI{AsL+ufUYN`~ZLbbvX{ ztMa=9%^yC5Ic7-HV^YGaqTDd+#fiyrqWy42bKbb;HxK|hwJSad*+*wCa05R=YmztD zp9npSM}fo39Rr4GWn3{=ql26Yh~)j&g^)yP4f(-y@~qt}+ANa5rFD~?p@)(Du8F#z zRC<(-rVn(0{!_mcY-209{<-?l9MczO^2dYfz$lXh9lK#k0Ew*;k?(%lO`bam`CF%A zFk1ma;q&P2=F@e(_p9CiOJRgQ(sI<)cXvm6N8)9Fy|`+dWK)=*zvzsd66-EX^IE$K zDh0afB|-<^ks+MLM;;2lTsAJ|DnGrL!}uiyXQVik7ioG6VpY7zUthPww;_0LewKcB zg$i;Cq}1krT1@Ugv9zppethFgNCf)A@(`DT)+p0VhAQ`wc1&rqUF$x&XbFRxKZ%8_ ziffYjIJOI9+e_5_O<1e33kMoXgj9Do55bicrQUW2%5G;4hivfsKjZ?( z&O`nhc|VP<^@RQ7ucgDtBd7&R?g!+Nlf=r8pdJ)U{QD9>rI^RwgpHNq+|JLJ)|6>z z?buwm_X*qeH8x`UpP(`Zr|V&X(#s3>+k26X+$a~>OlRb}{9n9clr<0Zjt^X|>BI(U z?Ej`Y(v7KoMzsGadDg^e@Fk7EZl{ft+R6A82rw^yyw1?$veEw5?z@`lc9+!GN{V2% zbaCDEPXyt*os@@co3!s)daq_SWol0An#3|Z^J{a0_diiSy$4FmZddcChMWSNf>^Wg z(s}n96AmHsem~eqmYNtvFdHu;1Sq@-J1WPIIoR2&jw!oprrJA*M62;RRd3>rq-KuM8*BWy`^&0icUQ#As{o_h*$< z4`a*UBEiz2_U+ft(;GI@H!Y@ZSUEW};>FFl_LWHQgvdFxZ-%Q!k&*1FpzX^3wD!bw zB1zB>u%Lv$*gSrg_nG%B`A?)tU>e;1u_yJNAn+D2Wxr)+l@vZ<~&1tL7+*Zf|27AOHA;R${?3PEC|`HNd6nPTm48S{1-N1sa|` z86^{lp13SGGJwWW~|v!R@u%yTC6h|cgzP1JErMj~>aWO;Ejq$HJXvyCmktgI}>dI#>v z_t)6e-^Z5+Tkk<4KkUfL_@l0FtNZoQXX}Q|P9)R3m15zhOA$>PWJsv*)B-<7dBP5S zN>LUm=IWzYT0QZ4KQzFsLu-6_bk~&er`N-KgSjxT%d+HtsxtK5sh}qys?t7sFpsHR{o9U6bVzp@PNng1@~vn+b$Wq5vR^5;M1*fvZNF z47ck6nID_&icjWKft|+XsvI-3LKQ3|iRF3iv-tA>%k5%flo9BCJ2IlOVEZW*u3k?8 zm4PF4bzY^m5mU9|xWFL{NV~VD;bEt&QyKqlsqxXw$Hx{?9Rd%V;Y1ADT6!RtzZc5u zpz%ZZ9)1>ul+SOae?zi=pMi(>BW{;1n-;Gv-{PQhHr%Y0AzXaa+{VzzA`M9?D7+t2 zES~B$-}FAQW=#lPb=L@VA+YD`)~2wI=)-D`2*f*cQu`XFU)vcGm^Z{(xMyYeQ+u)8VJ!z$XBqP!zx`?jUf zLGAGBT(Wd*)Ke-H%*4udrRfmI(#;vv>mkU5TD5Bn+Od6FVhQsJ(;cJ<&( zE3Q`@&A`C=KZ)5&=Sj(^Ym6u*rJtD=`)^q)WM}hjVND{ml@~C?=u&FmtX=%|Qd`N9 z!^m)2j0`nLE)_>Yvs`b}vxrL26Uk2d4)Tzn@@Mj3FOuyg!nDoU#ONl$W1LnlR1pxd zgoJOL;0Rck@nq%z^%t|Pcy5f9B^6ifv(NWppGMfX9jDIWYKz}WO7GLCoTOlSDN1qr3(1^Ny7=-ys@PEST97DYbnLJN@UP!7>8HnsYmn!0X z^t$yl;@IoDDf4#Ngq+ioy!t5A;|UQr5gr)l*cFiy#U7_7B~Jgb+5M2Oe$S94m!yvX zsbe{ExtjT@)VDjR?A+>h)>L5~&b=S1uJ@SldS23ZbUT^AMYDv65=r!EJ|Ck)+;h|G zxu1XczHPLBQcNPu`elZ_=`5ktiUYduuTQW@lXfrd}^p_u>FpFO8JGO6H4$L;st4=n{c5N>;31#7_Ph>40e$} zGoYYX5NG%0*e7zt7cpFYxDqMcBZFHFp*!Q;zjUWaaF0E}y^bswYWHgTHrkdx+drTA zRQ?$$_b_Uw7J%FJme(*oVp^)FZnl<{nudmkmiG59CS|ZWpiUOtJ^c!=ZS~CPr3pa* zi(ZeZbo6YWF#Z2%0nCXs-_%>3roGCUTkSX;J#Z~1=CB~5Wg#`s<$ss|DSnyyWTnH8 z7t>dw)cU5GtQaAbN+aTAIbUamoRfI$jkr(UM}$P*84?D9%`fKlJWr448e0x7Lq6T5 zzMJyVU;6s5rK&js1$6~PN++%q;G7QR!|3Cb96e?YU@bwqgf9`dM9`J@xU z6y2K2t;J!p^?GU^8$na)^DkJ6ta9ei2zRN)=^$0+n>~=dWqw}ay9>V0!}p65qt>94 zy4P)HW}50EnH5CAg4ip~xvH!*qV_JP~K}eCB|P?Zeu|x)1&v$ z-DTAErP9O5^I)H)DU18p$%srSgH$6ceVVr8Ys;m-nEfdzmgcZHL1@u6CTYVUA5WJ1 zm8o;~eoe*vJl|7yNL5)wW@d`Hi%oWUMaj!mnO9(Ef{46U3;Yw`lj;DV>bc*ByPWjo zleFY7Y7Il?mo48tkM5XPmo2bOnb`Nn$vJ0z5xd7Ft))B^zLEfCpg|Iqa?!pGUB(ay zU@IGPXe^o93n5{t3X34q=O>*aQlstI;Z~**xr)0zEKMlWT+rPg!w8dX>KX714n!UI zSSjH29Ej0q6LYz=6QvON5M=gCAtq81&<+d?l-oZ`E1!$uxU$x2IPOEsK+EvFnnjL3 zK@3(r3^pwZEcu@NCDgY9kywxl-aQP_-K~biWO>YgrYK{>fAm~lqF~!kp_c~6>MU2S zDEtSWBsXV?5VEWZkI!E70`U&TrwodaChNa_Z606d<1ku(p3GoYuFZ`Y`G_!R3Ujq{ z=3mjw^8RtvQS5qYB=jT_`L@2Q7`nSO<;};5UaNGiCp|IaB}53IymjqtN&Tfc$};Zf zPfVDLGvqyKrR-XD5BU_Cdd`dc4x=yf@sF14T~7bVFR3TU_y8t32o_@#lQ^Xoi|H#H zMma1i;vO9;uJqU&Yev{>mM3&abC?TB4>cuG`{07bW34CRdnv&^%(LP*8QvE7^rJFk z%vj4*F^soiRTF3MA`b`HwxUYai#HXmCQO88L(-zl;w*YzbCYT+RdU`Dm!E$HqU7Gj z6rFm0Z~6F>i`|*7=s-vHsNk+MexR$V%5cqYoBu6Izh{sB<0v<7*RW$}Q9iS*Oy>>A zX6?`*vqIs0v8QtFr{6knrBdXii$F~3X@v9# z4D`gVHwNr@(cX^RCfRy*48&^ks>O6o9W;|trs3HRJE(n0BPeK^d_E*TdWiD{h4&lH#fIyjkLkys zRqscl(1Sqi2b#M5h@nQ#ppzI)O~cSY&WE1(?VDzL(Jue{mL~w-*I%F zygZ#^OzyHrL-|iA+H|6nI9TD3>Vun>-S0ny7`cge1P@;it4gO%Wi!jbn$0<7I{F(c z9V(vdW2Z)8h!wo*Z3U^mNRKOvd%eShyRlJ6PVB4~eRMZ_8HJy>9+&1Rw3FIKH{2(M z8IhK-^2DuJuVt>sP82;CQ^y)?{qat;{pGW*7{o--9wu2Rk&gu^Er?yuZZ+!q(RPSW zMbB$@+Fszm6b*6)Hu&GcL%e0%&}%8{kR*%?g7G?#|S)qLD28W*f{Rei>(jI zD?N(gL3IhZTS!iZ!briN`ovM~=%F$UCKM?`t)$Ltq-jI1$q+f^Mf(nx1kDS!Fqyd>~_WA^z*ZX2|S6oswyeoQX_Mx{8?ysEiQpEuPXGrwwWHXm5A*>qz z!&OQQ+Gd91u(XHLH65d2!^!uy$LBG3vPh?mL6Sqz$u!~!-Y0g~hA(zKkrOWuVZ28r zQ&3a2q@t!auhCUN1!03iK@wOXDQrpgNz#bPKoxufI!kHy`G@H`J>mWS3F84Y4wgno z#}z4_crUxJLt|sAwI5&BB{0dl#gNElyh$3h&c2HBJTTPIb=@p39~`{LQX(Y8Nvs|1 zJvkNSLOc`_XwT$ijMk5$wm_UDgJmP!Ug#y zZJ>C$S6Y78BUE!KDHh0`9|3{085Z22tnAPh*lw(}z0Q zq)WOibG2>)t<9k3O6%x7F_nB#x%G zwTBZt6>T<|Rwm@s{kA)KM7VB^ZHow$)p^+-K7^nniRr%qKCzU%V~#nAa6@IbSQmfo zyI6q296GLXSx!G1c6(idawEDI=Q@JIc|3R-cN+q*>A4kr&l120Pv?prxE&o;m7Csh zC_^vq_<@s7Ulu`cAxjV8)7#=44#ce?GeHKhc`KTtgP%AQ@f1xTv7$Eil`eAz;?XY> zft$|WwjtdJgAr6t)OPOS4W}#yIj817%0MC#2Trgax9ASp zj)VdYyNb4^v|f^j(cSjT;x|7WsNBOH)nvn5MRpEM@8=;1d9`3Dc1*MMrFO%X$uWGf z`Ua0@8&wt~>UTQdCH`mQJBKL&i-oRFWsMfwrGBzeQd2MdadE^gEIylTKcMM^Jujhc zComsRW~cKOf*PU;USG8B66p^veqK$F4~vpr*gO48@ME3P^$%^0aP%K)0q4k4hDC8^ z@E>_(GOnHsS7G^1yTZuFq%~SogXc+G)q+y(5N+aTT7z*t8gm)8jl1RauD=JbBe*_p zK&#)fQOu>X%EZgn?(V~){b~vdF#MA1XJK;@-l*H3?g}WOC0PGC%`1>5{N`HBB~asL z;5|x3+v#tTDk@`%nV*JzXPZNXZWQ681g(g4LMS1s&0U0uJ7?3637>btS{#~k?wmAB%1mp)J0A{pdg`@ z9H)Sa;f37=OSPr;#NV9jN|RBeg8ktdkh08k2kbO)c~_jcul^srLGA+Sg_+gwmbEBNSigp$ zWm#*U@?yp+33=B(!C%=yxP9{ZY}8(hPq?u<$mu>qm5Q?RmazYTZX~+F&2=C|ByqtD zd81VEQ6a5{#^`Ftn3a2%74Ch@VLjC7(ncxq64)-S~Cuy?|Ogd4w z6rCSY`E5{`sf~%bhbfzzFMEb68l7B4>&zLWdJ}7GrpqHVIAtJ-JlSURYGa7dyJa4XU*3^TtIyTZ_a=BfG4>RPFSoxZ&Tv7j@HJDk zU%~fzLDY8r2K%uO6bykvB!Z|ggCw?WYw*lXh2CBL=;Jpn^mn}qpDm=K537w|7o!1C zU^C&*kA^VrU$j!hJJ!<9`-BGl%E6ay(dO_Hx{q8!whtSscme^>rT@P8uArjgER`1m zW}7%x?(Jiw{(8%U+r`cH5xs{({j$gI8YeBAvZI35DvFu4{b>pM7OYw3wDWsGvZJR3 z(+Tad+=jDTww^~h=!gb_oYw61_0iYxW;G^sse*+oyl@@h4W-?!;4ItAcdlIss(E=C z7f}9Xw4yV3LjD^Bj>fKzm)ncllLFpMm48hn|4#BoaG3P>$)R=!tXU6*8y=X;~_3qiK+GcmpWQgDYq0rgzIG_}hM7G|xThz66=dDnq z8zYQQm!M&EiI`335OVY*6JjA?sya|HqPYekyN|}F3VyAUOeE-?enLTQr<=L^`;;AR zcL{alIhaP_!rK}FVF9v_+EqM>in&1N={rCk3aYjPbSTz1lJK9)Hd)Ibquyru1hK?d zW8oZzOPZ`H7%KscNo@+@UYVq}CR}`c8MR5Vdc~+_Y=exw_-6B@ z3q|qdtt;d%*naZ649I}@X+DBYSPNL`flZf7t0M1s|7I#J3*}jIm|3QiC%%XL?i}Vr zw9i{7s5QDcZJ`ouIh&r3WH){CH>jZp-0bU-Jm$yq1`$6(-;YO?H7WN<9?~JLYUltv zm(D+6a`onKju7H_GM?qdU<6^&6EIrC)_wx&ARwGEIuu!5`lR7Z5d?6P;Fy58arxB! z5f>tK@m*bL2JCn7Z|aoTnBwQQS@U0he>gA&=X9eYe~J<&_sH;gMN_um1c~eq+LY)% zf80#-K2eF<*_&7EW&ro`XBDz{N~2K9@q zMD2%QdYXV^9ia+oi9N+?ad<{Vua00_^RHIXfQrX?k}#32WTph<=Hwm@e~udzw3tW? z0)dmSnagm>s!OKK%RXAv=vsULDFu@TTChfBk>(JpvZ~XQ0gO`qpZv!$nTTX8ie5-j zH=1DrFcKDJDK+M>G6j~vkpD%~mxn|7e*Zr+27@s6vW_K7B|?^@8ImnamQ;2nOZGkM zj1tpYuAe^E&4+utaVR zHZ4(>pnvVsl^iUg#zplm^YOX~Lu#ph5Z3o;EL^qiCD^8&={?67_ZyJC@~$(&s)6Ns z__>_j9CcrW8oz27eSQ~A4Qhn3`5>lkcOpLOSrU<@WV=fAi@;C2iCbA*z3XQ`$Iz{3 ze7#XF1BhX~#AtlI#Y@w%ca+@TrrF&T3AjtBq<1noGCEy5Qiho`^tm0c#s(}-1!sM< z$VdZ_*J`sl<*SF{AmGLDWNvYy(j8`-B)Mr(mNixV3&r1Ep%Qe7d# zfOWV2WN!-jmdCxAZR+^@$S;n_DdT$0%z6iJH@OtMzwDeX7_acY*RyVsBVtVpz>y~- zbG@@yT%PwwTpJi1{_NoD>gwc_Pr9zu`iL6+0QH$(Q?=Jc3^hZXZ5c#oDdIMBhrg~P zX9?WU?tJY`U%`Dh907r6v{W>!jOHn!>h(u-HOg>Z+d>Kmb#Ly#oG`L2bQHtSZmX#K zGHzcTojcj`^j}B)ZP;kS!da@|rZ?gFMFGu78@m24qd)oDjS#NdV!M;C7|$`Du7eOF zU3`&ztW9cTdp^~r@GgWZw^-K*&dN?r59ttT19+CB8~7+%?G88Nl&(SQn0kd-ZOCwA z-Jpz=PmFZIy-KU1263}w?F+*qUC{eHw)F-uz6{=37(rId14e3i=~+^2(mOAU23h9# zmFkhDYd9{bFCfV~;!y1|;I#_;aJojw2#eT%&|U_Q=ZYfU%&PO>x}uLhwRWexG4%0ZW=nHtHWV<`2eWi~DNNdFDy6;J&ggH~*=TCR-P^ix-v+;7zg3ndfpK+0f&&)-jMD;eve> zMTZIL(haC`uCLtKXbDLya?!tARp$$I7c*Tj_iqL7dm_4n-E}X5A;ZntugIlbQznza zbcl(S-Ndqp5UhpT_GWzj4pm+GE(RZM8!A+$F%u3MtAvWTB*V1%z z`?N10ug;IIuC89bd^yFSz_OT?mGz2gK#&S|jHjpP(7iw(9|#dt-SU?{gOW*4=G{=B zNH8MhkNHpay_~Y!f!6t%C$|T&jQig8fy0#(X2=U@N*4}_BI*T z&kgST<$kFyo_Kwx=Nzg=Br#L$u}gsNmxqyin##P>>ngOXQ~T#&K8^n!x<}D^ANCU? zWX=s8Dk*)_`dk3CMwdvbMXiw%8ROD!~8=lh8Sd;A)3DD^WpOQ%)v%o&D(ZxS=dend6<8yLMKZ8M( zA9vUUN8co;8H*#2y26J`N%px($c6Hb4r5_rA@)s%{RBD`*`Irfem z){68t`^NgDnq5ESTI(9?hNFR&suxZK_}uR^AOEz;!KBT_6>jN`YK9F=Xyf(!Kw&|& zPtW)NhnumJe~mgYeB3dS#!Tz(=hWP@ZQnYZ^E{sQW8H^<1lo^q}jAcj)=xQH zZ`hQgk`i}}V~BC;h0R2i43Qps=OI1$OSrJ7YwEPy>vX|Jm#N;&u=g$ROA@c)f?wQN zmJ>LGf2IcLf2s{C#cOMD=D%lgxW|c{wi|st%O=Jn1gN9DKYGT7-Bqg)TuZDH3d%Qa z$Cg$F2Ti@-^)9tV7p!hGABJpFzSX_p>yk=hR-Z(v^XaQx&o_ZayaxbvRyVhsLB3dyFbRlH! zR$86cvPC*#AYovPBli_kZnu)F1&PBKknobqWKO)9fq}lZGe1ZA)6)fAGVNG5c>lWP zMh*xa^+k3|kgjHXcwDlX*&(fsjQQky2+yDK0k%SEFrS{b8XC?Zr7?JN?pxq_bB}92 zSMJ!Bg+>9!51W#S4Q>J0aC14MrrhzM+~&ADEbXT2C(PLUA+p-07gMl!-^HH`R=-lW zN$D6RukKynlRFh0!q+vtu}?!m*`t~|#jy?Dl4NY)VP%t~g3qxo+97E{z3$&h%md|;FsBWOPc?R|E-^u z>!LAvkpNplQLFz};ceQa#_uLpIr}CXd)f2^IUYf@y!o`&QSOX!c^;q#ker+1Rj9Z; zy78Q4u$ey9#>=91IMmfu&t2o<#WT@pu{-d%RF=F-WpQO}(*X(g+qb;4h6+n_bN+f> z8Y%isUMT_I>m5crSmWcBJ>yhuy!jLH141|c!U@HolqhQYGox@;wj=-?;l>^I~B6IJ%C;yHaIB% z!q?x#>$od+vxo+pdOpsgi2~hj+~}s6BlMkJs%|&FnhGR~3H^ljg621ynh|cR$lt@4W~Isk zF*j~ne_PgC6Ye{G+tSQKy`I0VdsQ<^Nl*1;H+(PkEeJYhRx3^KkCgIH?sl*BBVdK#d1cM{f*E)igcd8@S<7S0BF17!$57Wl>l6R(JAm3^eFF*xL)u&eM`j)|o%Z3lJ`2Xen5`ANEA8WZ7zvxWJ0eWH2 zN(?Hl(@hVuZ7jpDy-;iV5bPv?s4*k@=ZUXEa;q*+)|)veR>0)ip1)vtFV0U??gJtF zJi6aS=3I!<3sTw3rxu2hRFinxSnd9l73-1VJu8RpXXzWybgA=Y)JSc-wes8v{QdDc zx_bCKiS9qMn}s>fh2>nA0z}{Fu^^4+mc!xcg)TN=*{y4T+&BsCX&0iz?%qX<$!J@Y z(_+bTFBl+0I^mqP3rZP);-1$wDjLH6I*Zf<=bZA#CT^9;6d@hjR`a?P8EYWGfGD(< z1fZo{<&9e%aa+Nk2v#=F$wIKt?Xy&jZ=8Z>%-|m9?mpfATC09l`2TAGm_=T!1+qmP zKAeSm{#9JX#G$1Y?B|GQ-PzjDpL7MnPBHSOF4m3rJSXk98=1A2?4`bbRmq|Ex7Xv} zGzG#x@x@IMSrc2I}M$I(gpy7u=5v;j5pL;NmG)18axN9!|DEXu#1mf zV;+fgt+UuF1YgZswxk+hI2$khXjbvH#$d3eG!q7aWgJY_EU~V!WxUG&QS#iYzET-G z$>(Hk!KSj+>SV)G@mZJqwtq6!)`aM!nPl^fvca{^yn=aS#l$JKukPJL|Ew~N9M~t* zVaX(4Bf2%MFwMj5MF9~;MYbRjbq^eGaF;*sU8p-`0K00CR|IE}v#jx`A1|IolJY#u z>hi)IP1Md9HndnKOjU>d1u2Kwd0eLY2cMB1wJygOvYaSn5v~ul`r43)_?RfNj}wYQ{euM%5mQg$JRM zE$*hu$lLwdIw&)>fxx|eg5P6)alp8hj2U9z9;eM;sP!K>ymC9cJ(M=NQumyi<$?19 zE1m_S3w?5bfj%GQyH_ZgZer*D-iN`z?t&8!9*hP7&Kq-yRZs$eZJNgV(upAbj^jVm zqR7Q0b9R>#{=Ia*Cap{YK?wQK>3o=D(QzIwsJL2@r6fw(E00bm@leoxSA` zY;DnByv%+R%sKb`6!MeW{|J_nxSy~L37u_RUUH&zVj{5G=$n806i1F|emP%vE*>3^ zM@X*?7)DpH5JP0(dd%1QWAO16z_TRwd=v~FU2*Gap!;Rzj6{fSlJx&TCd!+ViMJ61 z7kVGxpD<-&fBqx7kE_J!e06kUBYyZ#ndn_kq4@KRza?-Zg44=KtgRB62bOUI!EKDj zzsFRVsnLI>hsP%$-{?P3R0?Br=Dy!EYLoIpuot&nfWBkU*O67L;B5zYaG7uK_mkqh zzFx3teRnE9pP?N+gyu>zS98YLFr?;7&t zp)|cj)J4LTf1M_=@VEm#VDC}8FIlPwo=|_{WZp}y`-(7_=){ParZSOp>H3k|hZh!t z=h!r-vTUgA4!_7@!zUlEj1X@d&`m*cR|$t|_Vd?!rN${oE(F4FKPm_K`l9Lb;j|J^ zWcNc)oBL-H8+946P_3^2TVDa^8_ICBX%t5&$f zHCYGoKHi5i=#yVfWEY4ZLKSPu{pKEQ2}<~B2vmEIg#Mu`O(L#rP0zESUt2oNYWju2 z{E$tf54Y)|pyM5n;}-Bz<9NT|RfOb>ot9Eb&Eg#5VEwG!gPAlwxBHftx!g*g!?X(d z3?oY5kfmjssn`Xz9Unzt`kvCRtgQPovPv2?-GsH>2~MNj1XLZJb#!V|!1xh9c>y*D zjQU-8RQ=kf*ALhi!t%??+P!x>CvXinm19c^2o~^44mK67-m$sxRTS-K$#y1>}PQd z&$f%pcQu`{=y)Bj^h22|rups(r9%NmGWuHT>x>y(u;VdmQmXz`9F%jM45mDi`gQor z{U_~f4R4fr?d05VI78^j$0eeN;KgsNK@F{p3GjZbEl*%m@zq5DC zj_LNBZ$%rH1wKb^qL;Na?7>A|kgM_XC0+3Cny|@a>8~*faiH9#m*EpMSQ+Szpmywx z>5L*|L>fsBT7b0T=wzl!wk&PYu8&&Umc;MCz%ILlP%QW_eD0d#l3cddgPn-GE$Zsd z^wZNZ%suaBydw$;^JOUA`&jF(bo+;GL>ZH5e)0M1Ctet{4aMkcpYOjGIG@uZ3&Gni zi&Ju5^zxN7aMOVTmNHE%b)vFYZ{p8WGm~CwJ+PShAnYHL=r zbHQvKlb;2;a#D80e7EX4iRIHuR_@a%{L*(4?-52*JQ=+k1aP)q>+w3>wIm%FlH~S&QuRS#O*?ZF{ABVM~EaGqvg3!1@Ey z8;#kh;IbUg!$o6WeGNkL^gdh8Avp>0>jC!NopswsFC`X;{tKDSH%>h~-6^EE48J)q zmzT8K`k2Qq82j+~T=m}T9V@dUXaFCg9QVh=PmJ+y5yF}OI}E{S6yz6fB^;iG9MBZ%6KyZ1~5l9%t|qe3?BOl zn}UGQs2ENMTy#cc{SoSA$P68U-<-^0z9wSwfv_uD7Xu_L^T#tU1fLA)SMF_~*OugH zO8f;DY2$ZtW%Cz53SR})XJsZLBSTIC^|3`F$mw^RDx>)8v{LIS>y@+YEA*7*Nk;mB z+k6`m4VgB7O9RWPl}TyGgMH+2hs#67s}U(?nkeA-@#6>oL?WCV9H!SB6G0I*MWeJl z7~BSV6nE&kj_qrTorxPB_L-V^)l=%Xa(#0A?kA(@%SbwAIEUT|gu<~0==i*31^HNo z_aI_3&rl~HnI8`*xfvO_6;$+JpygWR|8prxevxbmaV+8m$y)g-X8GI}nQ><`PFmUw ziMyIqzKhWv+;FupAFE(T_zE7Otn_8vejn?Bw*-yV#Vq2;rDs3K0uYladiMhA2=y*3 z)^!q0ZSY_5Nq^S$$xuGEeFYhRW3EgerTN;>gHX01{8AXcm-b6{qAYlOp&NJD0u9POc|-yFES6OJOR{}8yd;V>i+jM`dhOLX^Zf9q zfL{}yS{}n<@!T0IC$BLZ>3d%i6N5I)T{apurX!TdYlV!upJr$TO@|&R*mf5GJr;&O=6mqz9FOe%Lu=sQWZlSdI0FO2$1BrN*FMs} ze6tmrlf3r(^DLA<2cW)!{0f)p5Xb2X0VwIll>u^S#pIpgb~i8Z`wu#j%QEsDG>b49SRiQy=T2FdVoX#L&wm9PoHy|=+#mBV&@ z5kKs+mLp`j1dvCp)fml42V8j;6n2pBww$ z%6y{}VV-36mkrcH4b{FnGIXA2wsEYv?(4#e2kz@O_Qd*UV7g_g4U+>2lKG^{sobIy zIrs}EHK3u}X!(Dhb4NlMhBZUQ$;T_85>P*s^!4EqdMx;g=st-@?|$>jJyS?sP)T4z zax+89qJK*^7po(tJ`TSy%WIX~XMf2iByu6N!f&qWbA#?FMlNcZ1;yIUjNhvD5lqP= z51)Uk>70=%I-grpnofqFpb6zxvkJ3mZ)J8aHuOQX7g&tI|;Z_?Uo!5zh~V z8`~Ha6tL948B~%$?is6%3mjuKduIpKFW`JWGA!MLCp&TFyFv{JN3OoyaoV2=;rsmM zA~A0IB=UaIf&OsB$Q!eNhxIzZZenR_85U{u&;#-)VMpFav0>xtEL5LcO1`${x5B>|611ID*vI-q&+^ zyjmo5>2IH?rzgxnravQD@`}~zer5v*W+fU#8EBe)F+rO zC(FS8O7Z3QepB0dPG7XWw%RaxFm)Ki1M81fYXw(hb&BiN7kI()1w1O@wZ{%->mx&4 zH|#?*F|x|l=}h?o0N94@QzmbaRky&bsBQXpf|j&niblwUdP2)x8th8``Bwd8el2NN zIA;##8Po@uLw`AAXfkY*_35JQX@~)ai=)JC<>f>n=AKjGY231t9wjocayh0v5X2KdeM zUY9<8ZwqYF`MAA+*=u@OI@ePIdNV#>B;JJCT*hBF*Vztx7i&HVx_wkQPG!eC7>-!} z8QH}sBsQAbVXMq@t*bHmhz&BbZ2?&Q3kJAhYX+n%hYO*`uj<)Q)F<`wP#%+p8QFfR zO=4VnhyU6NPN+*VJg9yB%~;^C?H#`ZfAPIu&e@{Zj@>Y2bG({MT68$Ukgu=#vnD7}Qp@4OZk`^(NUX1~_0wS3AJ$a4hIb7O4Hl6~vZ%tiAp3Qi>!c zvx4mKC3JT6lkLZN2=`{7>p7yW#8=Ol=r55mxijR#@Tn?5FXRKr}+BjA^JT0 zUlijiMRAGG=ffXB=d#^6n6IW(36#WQsuy#L!3G7G*U*KPuEKyPbzBYWmWYb;;PPjx zSfLp9*$uS(Dv9qagoPAnqs5Yw^!%lr!`t3-B$2}OCfP%8bGm*q!EU>^g))vAP2SJx zxnBe`ui?`6FSDng+N_lCw&hMuX@DN1@1Jxae$p$gp0&R>YaE)P^42=uv&SAZ zMbqJ3o$l9ER?heHq*g|I5<@mO>7@3q*$88YaOO60SaaB!LrAg6@83(l^6pa35E$d} z2rTw)sO}iuoSg?v9@A7lt`R*hy$_fpEN*ybFXt2?;|GR%i|GHJgdgy2vibYd6j|YB zOXT-g$>Dx0q^tJDh2aP3m3#6Sadh>neNaj>1M)XCGxP>@Q#@zRGe{Qn*mD`L6HJsD zvtoVlP3cWDIgan7L??`O07GuPr36-6LbFe6>8G5HQ2X?kyEmxInUQxaRfBzd6Vb?t z>nTZ6gu{k)>LCF~xQVp3wq|L)U1U+Q^y2&X%huJ6JO5s}=<4dGp0y2{bhjTLRVy6q z*UCsXYc*S%;o+0n?eV_2|2Ho$!f6Xu!Gy@Ikp_w+`qA?uj{Xq#d)7R+ydE)Kx*J@- zPh%A*YuvTtn#(EP@YKf%OyyW3bJd(X0&>67dS8*Z+58Jn3P(DMg9AmhO=Q7U;M(#> z;zNfl6WQKaIf45$fuZgFvx#3NMG3qPJq`Rqp__2ce3uhA8SfJS%V^-E|g3x^fw@gy)$QjmNjb952&L6v6 zkc^s1e0ui9y%mwLg`Af+UUH^~;(ddGJM`%O2Y3k-`gO<=Bi?wYl`c%eBCc6 z6Zoiyqj~6e6Epu73$pZBQ0(rA96bAgYJbvdo6dp?QvuIq{$aRRcAzK#$!Iz z#x5bq|8O#B-^=r2zR@wS9-J2v`;L_Ja+XwvaaPR6VKSODR%lFXH6A{{+fnh^ua@C8 zC4PQ)zp_5I#bQlFHgS@or@q$w&)GQXO76Yr3dq$zlE`!gw50+4G}b%tcr#8n88~wQ zD_?-E(+E<^*Wt(BDvn&Z&vUgkU7eh6x??ddeFWehE;a=}q}bNy z;u{-({CTGIg-_`Ti>t7le8*!TGweng6zp@mB_rU!ui;cUnuZB!67INMznS&4-%PIslGx+~Js3ec;d3yNGieNo-9^4O0WqK3-eQ7Fs2qy z#dwC^ytjmY6un0=6qx;KJY0()OPO$)e!hwPCXaMlA8JUI`&&|E1r?}|_a(fWJ0BN_ z`7W=R)ZE<6M0mH`M*I>Pk<=b;O%iFEj5t)jJ^5yLAN>~e!~=LJ>tiefwL+;FKYTr< zHO_&(+}R?q-u5T+yT^Ni`r7sN0XKF6AX)-;Fp21uzUl|3Bo!Y~|D4$mKM2w5!$Yt-)Ha%2?P6m8<#zMR|QlR!tqK&Zvj0nU8*9a>$)GZ@^o+e z5nq{yg8%k{RL=dG#~AY4I;kMKS&Jo|x&1fLMbn{-YlUWg>#grnGh%K(18t{rKmlw09PeajvIilR>4Fqg`{Cfb^? z@`Wsoo{kp}T`CWV?d|Ok!HwzXDia$EIU)Xg|L$iKj(vAxN}9PGXebMaRz!14>`2?z z?mW?1!R@&a{Wh9t;6XEvn>mVGLSOF$vcw)Ft3a?5YY;-+EyMl$%&P4hNsuhyPOyZ) zZ*7F-;bbt_+Z(awUtsq1)>f^%7iDh9;o3Jae&ajWv)e0i^z+W4W{%;G=YGDsVz@z1-$HRd+)^$^!CbZrG7x-8D7J~b#dg3ZyHHS4Hz8-f*#{`SP)Dll*p|c zQ24xVHAiys-qeSZl+MjeuZifTc0(qZ>$m7RWZKi4uZa^aeNOyIKV^2|(?Hbbr`xSt zBGiK)a-Ngq#{Gusf`V3!)-O4Z#xLbfw9WIyM5FQX5-e}#-<&*c#0RL~S?sxygQJmT zt+OX<1KkVEWKx*n68UU;%y}-|84;6#W&UONp)G@4oiHZk3q;;1q|hpctz=3n%@Qm> z>}`B!r!I#PU1nH#g93NYHf%o5iTovTEMA|}$NsLW6vQDdX>Ma%p!-fBW%kBC`qp1? z^=@tI@~v;K>l0W&rH4ojmyCdl6Jz{Vl%OJa*Fl1#3JP6qo;wazh<;uGtaY27{@I6` ze*U{GlaB6>-Hj+vhv)M%-X}vz2?U@(CQ=zDNZE_Txef7ijB_RT(%|T<8Qj|F|8}dX zVotCReBQo0?!s6;#ONn?enBrNUKY;v?HLOyt)d4fTT(Kqp-~sS3MFkThJYL>Kt z?~*#T-om>G+WU9IrJT$Tq(3RvL z)AnA!&}%R@A=eAVvo z;1%w1z??_V_*<10h+?HzV%PR?bAtvSSd+3PC9N0(3s|ZyzMZM`m6^ zvAgs$FXz#`tfH>ums7d?ZXZng`t@8$<-f5BLPhN78J!A4Vl^+?hs-X7jgAl4GAPnN z8})VQU+Y=GKfXQ2fHch5s&*}46S|Q9=I;&SzTG;v6kNV*i9;-;s3WjA>D_4SS0Zg# zWq)^XaN%d*C*y0BlD*){6#9Pa7=HYtttGF$W(Qub=84g4Kv{_)K3aQ38s0YRai4D@KLBvG=%=WF-6qf}BxYcB?`< zawHs@d;3bZZo0H?4gTr=X5#hJ_S-uq*=7bZ1(j8jK*>x6K>o%Dl58>iXUnT@p0WEi zP`B86&Jf5#L1~pig=}mK)ZTzd=?0ICw+Uu<&}o%L4}SQ(-uoLw;+$i1#Pk&Y{R6ed zL<9QTnigs<#&7*%p5Gk608PVt)wY`+cG$OA;IdaCHot@ks6QS#s0a!SabSZk4tN1e z9m-G91gJ0}1J`W;C>f)U*VSVbIx#Br(*@Fqi^#XPm?WM){FvN2#b`Z21v)@!6Vi%RV+dHf(=gj+;ffDnaiwD_p`& zOyBBMftQ{Za4My<2@A5wUGz2t0I!N;3H#YRS9<%Wp7$enj5X?qs#z$?CUO^sM#YrGm^)1VVhfza#|>b zJ+%YU;**)Fz^7;Byt%W>H}4?@_mt9Nv&X{qC2;ATw~&RlHLh>gHQ zK@^_HH*asK_)V@bJRlaYF7l9qcL~)U67tQmg444y6yKmjcO}_O^mL`L(&J;#4FIQq z^fJ9TSVHuxK9fB=x+M6gtr-T~a6r^9#{bf%!{3gFFq$01cF4s^yXR$^ z5t84=MN;V?y1ZlhE={00Cxyy&6U6*<3PM=y;=$y1f#RS*$ibu*-VTlDTFx;L@iC)z zJia2XA_o}%!OwltAD%qH6j|t!XS7gu0~HY1xbN6?7H_wS>D|WkK@x|3b!U@tP5|N} z2crGe&pY^i0or<_=U5CI$8#Lh^w9|P1D~nG$m-D6N?qZGYV*ugs5wuZz0WhIToiB6 z`lt~;S9^z+s4tcH+v#Y-@T-Nwyg}h?6^j7nD@{SnB5Mv%CraEQBr-!y3zC8Kd%}VaCwk4T3u}U)ipe+)IW} z3n`!CZI>^MKF^pHR)u$KFIr&vwB?fKpV=3As`Tr*M6w=Hq&oeL7WN;pZ!8UPLLC#< zI8}fay-hOF&i(c0*O2>g_{Kw#<)ste^kYziY}}T~de~M+)a}pOPTc_TD~c{QKY3wS z;@HFdTbfyK9PYrh{j~g#L$RfyRyK&S2Xn6XNbHg=xL{w%M2(f_VH~t}1pGb|y!Mi8 zU|KT6GZut%bVMXmlMb2S`vEtZix#AV^@~y&(l4IALYLZTn0m}(j-(<|4~^nMV`*2MKb}WLL_re=orCcd_8|8Bbh!YZqDr>FWMf2sGL7m!% zI=aOoOd8IXVPFhrCp=82B`KElt#w$c7VQk0sUZh3?DIFT>?9yohyOJ$+v zYiRsm9MkHWGs6kx{wh=gDauw7SN=iXV>D&I9KfymX3VW-T4 z_rjLd{llE;wOT64z&0}^c!j*nZkC$=3lWSLCy5DQ;%b&FurN6PmDOU76)DP5Ow&H( z;&3$nVN;U)wce~VVkocX9(JoPVO>ysWV}w5=h)-wGy4N5Dj4OfwY05me zQlXH^9j5wZ(tOLV0E@9}QV$4&DH+*ZOCVVI$aW3r>pzneoctU(0`4Em#sXJb1^aGZArrkD; zA9T$_fRHkiBb`soIm49i1P+(;sHSDmuor{bCQ{=|kZGn{f$TWDD*!QkI{P_afj%>% z(rMSEqW;u=aIK)8J?2?Mt}wDMpVz@TcJE%`WqjQP1KcCqP4q|*Ca?(a;{MGne{v#Z zWfk&>66$OJzpg9&S9BSL7G|vz`?R%5T{LmIE#=p2`BQ)3*|TRhU;O5q7NTmIu$Ql% z;%3eyAL3R=){dVLKIeWq#h}D;`|R)jqlXjc<*63=?5%#lo6yWjP3KdsapMTp&5GGSxbU)21UIjC=`C_09$dt?k zlVW6z;dHWmHW_!MxLQ2sxYF)}o{0}#6pEF8Y<1DculL_qAs{C9RH|L=DdUNe{DQ|R zgZy6#3m0=}q^D5G`tadH?~tFp0RdeG1s3qi59Br#f~OV3y%OAfD$W;-qH6;jSYcKx zSMB|mHu~a2{)`6SR*6FJM+;vF`LEJx=g-F=gwHO46py4eX;dgNBiiq8mCuga;diA> z-aW)dc7ulNP2p{~C>Z_6SB?Bh@DGeY1O@k(BdeHX>q}dE+-7 z`!XSanc{r;6tb>i*tz5?}XMZoJt&yTyw@h8~o4!Vlv6 zM(n}Rw;(Khx7hx*qDxhB|2Y{v_PptMg`2szw;UidA2>o-`)NNm%>Z*16K(lM+P0tk z++bCb{m~*jynt9g9%sY;1n)ZKk`ASq(wQam#GBH{1k*V}o+%4ZR%I_9rukM3oVs5X zoEvLC(3bSq=PI=z3^u4idgDtUHNg$Yq0pxfJY}K`neo7pIiCH)3*pgBUH1JH}d|5mHHoRFvmf1h=c_9B>4SQb8CEOEXf zTAuL9d3Efq?#ql6B6+wPh?n$pX9iktZ(fC((QdYGhJDXC4>gWExKRkv#tEUbM&98x zQqJ1M*Ydis&Fdqjm#&R%S4ye0KM=^BzMRE*BqX7#u3~}mPYI$9M*Z+6!B95v+%7@t zKruTUvqj_@e|`a}mPB!_3--)?>(ZIF>CfYPYvLpN|=U zz&h8@h7o@lsVvac2DqTWkq>%rivnElDgJ-LVKM2n7D?bwqdm&-paIgr#Y{#1D_~K# zgsJ+?wObR(dyS1!fK2{p7!v8b-K~f3L#e7@{fr9*SL<3kb0vd6k2A#;s~w3cIC z8AFltJgG7T$z}=t=z3B&W;=>KJh!A|VtCk@9~HSqq-nR;aAU``9LqW(<&L2)WQ?u- zsbw>rVCgh_{4bDqB+2{kC+cbiu(1oOKBB7r(8%)d4uv@_s(hgTo5IkpOy7QX{~oNS zI`Oe6S}%h>&1h|DNk)ZK{4T?8N8Frmd$aMW!;J?bK1!vs|2~Z2MRCGwW}f^+MC;LBR!IJKH2^+G z+t=s2Y|eO@8)1{!zCnfg;fuQ?1jp7VJdnsi@e8qvPLTgZsPE#dPu(p+3x)8st0r^% z%}1+~dAQC#@$b}oESsg<))oN(^0Sk zk{cg)&Oj}=x{o*LeLt{bv)o%1nX3CVNbf+*o~)kO>RFFmuY-~iGiq=Y#LIJPT}%8b zXV&@>`B*9^4vQ`s^rrUUjs&VV_Uh{H@6Ai;!@qgG<;a3C@-fBLwBK5Q4rp#1jr)LT zQdIZ1{M<~tT6ZUkNsMy2ecLwk;^{X-mj30a8n_7RqG9Gedc(&YZYI3+g)k%|`>_x=T3W$+Uv*o+BnZmO3;%Hf!=+sqlO z)o1uNsT1TP2A(-8Pi=ix{vqcFRY16VjO`<6Um!$dhQX99S@0ie`=PK<8K6-3k9S#) zqF3yfKY)HW!6U8_`@*&<`)82>KJ*IypY06E%M@ESX1}J?k`CXz3r$SCL;mxD8o865 zSdBA05|HnhH6gZ}s9_`iVNS$mpy21^7@^)Qkd1!6f^YvKM zpYM!vHydZ55rKb9Cc?ZgK7tCXqS5iFZ}qS8ufil=CwoW(9MSio05^GscIR(s}fv@0@nP#S9LyC(aQVJ z4yGC3&%g+fymg^EUC+YNH~4N$?Bb9jf3di6M6DNVYYc(!%t~Q#$ z*V#Rbw(mK%PZ$#5*mt}Rw=4D)kbd`Q^D*S{X}G#DmaApBvm<3b2$D74xD%T69Nun( z^67$6gT5`L)3ssJ&I^8u!mEWr2>tjwCPzwRe5i*0`LU-ghfLB!5v%h!D(PyZT0TCm zs_}sGghh@vmlL`5c7MYE-*0qu91FbZ6`fu~QGPKDUtw1pFq%Up<@9E%VCqU->?5Bb z?tTDjH50`!mms}-O!{Z2u=AI?cSHAI+=EXAwCC?MuE&Bkr{P&vOjup;WibLT)El$2 z_#&(lC?DV-f+sI!;6~p8UTD0FB;H)S>Fmf-a&)?JDO9;|QeMQb8#Y_bF*h@cbS|ag zpzN>9+QL!y7Nr+(R26HE9{ia8bo)kgStF%g{S{Fdjeg^4ZNI#Bi?U=AvHbJpZUpJ4 z08;DtCT?S(`uE-bkF5Zv!x4|mDCS>fVdX$AG|&cS`5>T^guPg{MZ@R&jBddEvTmiok~wTIjxl|c96gfB3DTI%fCYA$r%urWa!Kd`XV z1$(8a#OT1#20uRUU8PZJiC-EJa^QD{rF{X9`jr^^Ye@;6Bdylw48A6HjCVG6u1N)5 zr0f-}pY4R>A!brYUHSgc?)3wxHPtwK6CkINFSxQvVw^LxzlwMarA2opZ&W+tzQA-?2Di0M{~N;$4N0G1ez=a z3!|uvc2k>M+r14NP?O$&Q{@6p{RKZuYqqvdm(}<|Bf25>Rujeht*?PhqYJ}qwGwf= z8$V45=WWyhuH436L;1keNg)!=_NP6FOT&7 zzSy81wCMfrPIsA05!6l>v~-VIxzDK?k!zot0Er49r>sxIy7WBoCJ0zQwzUUJ&py{HM(rMgGD}su$#af8yi3 ziaQjqx=iC=xGfalg~prWce9^c7m?0J9z4p#`DkA129{$*`BXl)qhR3Lyc5Sw*dc}> zB8tmm$IX0qr>4^2n^69-SShoXp-#Kk`PFwE{I3n6wx)}|VmK@7>+257jVID2>O&4< z5_49%x(!XmT<=C4zs#A)t~CiEFP4<9)11+${kHph+2RKyndM&REQq^ln@hn*w0E3w zVJ-u40{;#T$pdYm@DF0>Kmlx(ScF*rFgB=kmfVlIgd!ZVwD{+D-|6bnn{(mjk84V> zqm*JfSCI$D!pTH18Hs!uu9>zANG2ti=VLYJZ48RW%E! zyu{?HoB%uJxYzX^iqWmHTbGrfA+LSLY$@yI;QPK!y>xxP)~ij`mQ*U=s`m(`loZd; zZ}9Vi*P3ti{k%srzpE-EMSEe|1ecq@@Axta&ixoSCgkhauY2t7%b?q5JPP?k(e>7e zh=ULM8XOqylYsB5tc<+*7xDG9E+u1%e(fb-?*pWE6- zK(+ESoKZ%7H}RWTSmY|aMgm!pgE5O9GQsc8#xb#%YB24u(-ud`3@nty`mn#j2)~Tz zy4v8c-Y^HUuH3Q0$4{Qrawdll*6VX>hW;2DMysl^hyUV+vVZf4>k=e19{af7U}wa?cB=3b`FLTP=`O_9+~I{Wvph(cf_Qa8-$k0Us_FrB| zpAQvZC(5FHb6H(sBE!WuSQtSQ@p*S$`?b$BaN-<>^R7(#j7|&|oeH0Md=`!8XI5>Op z$~{z@w20FDaR^E;Y6rpP=pMU&dMT`vz2!Z~d;Z6bo@oZ5e< zNQ=)d$c?XQ;jNH;U%9$ah#aGn8pOTq!FQ}Hc>k^=a~kmaR%dcKO8P$oA{@Zj`){>Y zr2C&*!85;(-RrVBpLrP+OxQ8#3gXhG5@q64BhTc{e(HNa^yOTa?eY1_y=5}iAJy9- zZVq7<+CRV7Sihzf=m;)r7t44*Oja{ARfY@o;C|21ag5>Y#-lJ{r%wtgq=uhosWpai z9wY9?63L&fr+SGJ<&xTdxWt5WgFme=cXj>tTEPcHzX?%W%}{GLyLe9C_Jj)z;YU$W zK)XAc)lHei>RBl$TE6ys>qTJe9&OT3;~*SkHeh&xT$HpoD_A>MTUD^kXa2QEnK@N8 zfBavYfWKG#e*be@r}!MQ(Cf1H>!HbzkEDn!A`#v$8yVEuoikACWy^U=&$$%o?@I(K zhPpw687&a};O&406Z%7HN>+OoHoJuId=IljUxW2Fqh>aDBP4zKG!@{z*7cdZ*e}lT zM@L$zVsz{X2pga3sE*z4OV!2WeaW5a!X7(AwvFc!(N<RouzpM!T5u?)j_YN4nx7oj|1aId;{`5cqPgQ2di0`;zx2 z{{2GU5ALQ5pL0PjD!|SWX1Chkm9U70BI4`6E zs9H#6P*avqqLkJ|+La}igiJj@5X;OXIpw>^x~XxaD->-TZm93j*Zo1FKdG(|+bvH$ zruA47X^sG=W#aJZEShyO+44}tTg1c>&gl8V_s+k5`jmOUkki>;ONX|*+ks8#ajBxX z??RKnGfxjOr4<@`{U0r4XpG1kXXIoPnufc+OxE9$OZzZ!tFNSwoA8I)S6GCP$809> zFNWbp5R=lbq%bw)o$z&;WR~y^ZaEqPY6c0KAV<>7vhPYlDM}_BA~GpT&!nOC+&P-+ z?fquy%0mSxC0<(OlLrREQ&256(CJNaFU88|tsPX+o)^gxff9hnwrpDBcCdus!2sT* z@wOvPaxX)Li>DB8Kf&<5)-Wo%FEJmk0TQ61ktf7@Ro8E^0*U+X@1rI{XKrPKCbyB__KjWku|vX5dl^xLqI@?HTGOv36p*h^4Z#X0#D)Lxc5Vi ziFt1=<~!ex2+DtB_)_y;*clk^%{Tr{2Cu>aBSAwn>*l^F1t=qn0rszLXME$~44C6P5soxS2#{z4{Xria=@kxHi^P1$x6Ir+qs|GwHysAaHLyI$bH)?`zBOR3tiH?#+1 zs0W2zwP%M1M`1WZ+2ItAke;v)X_TjJ)TldY)-d(ivEO*aQ5m?)0RuANgmgNzyHC6z zA^91GKUKMVl`KL-Wd3a6OcRtdws$yqZhZAYqLFK{JD&j5B7mHa$z4(DSoILZ*pLr@ zyk3zMti?2Vq#$CoJ%{%& z&~dA4@LN;CM~ngt0Vm3!Np)yjHFlc7MlV7|Bk)a$>4O(CuvD#o5X;mX^mVRDK8~n% z6ZuHB>GK zY%~qh`%@bk=-Y;~|9=-?vr4XMnSqHeGqYbmUjHrQ4?8E#qDeu)DqoT_#~{7+lh?m} zo-~P&RW$i^$c$}1t0=D+ID!A&=O3SY)|2DF&Y#j z%;ZA&Jn^}oz3Z$SPS^2^ATU09^3I+2_xtIs+k*krA7na4*z2tXzRBZVVLn##I(pEU zuuZM%2&f6N5{7?(I36gW@esx4S!Vo3vGJ~?_yFwV5Y@aZ8+et=I(NGa%;+Gw|h8zr;MGY)eLtO`j4^G&Q9ZG8kP_OeVBz$;wM zFY~`Na=!l*tyEWDUCmwN6ruhw4Wq=%mbZx^(^@9kXg|MuCjmvqHi${}#?SX@u4W$R zZIV>(&#of4S&IXgPM~PqDVGz*&a6UeIp|0c95J@;*m|V;QTJV1;u5w9K9bU}L!yqk z{jHL6D@O2*4ZIXs6(APV@o^9e`yh@;s8rX0%?<6QY67gAHLSgkbvbZ@zgta zrX(b4@6X*R$qlb^n5)eGYSkxu=L{QQDe%2C2@QS4q|SfB`}ScSAKIPsNSqH`>gQ`` zHKN24I>4@QpI_iP)Yh{R$L=P>#Y{3THWkB7gB$&3{~}4=hIW^Kll4oc`BUVCZk4hO zY6BnMP-5_N^LSn+B74FK-|8a|KbEP==m?uOyZ(iOh&Ndm+Dai{tz=C4l_mD_WD4tA z0ei6nmQw55-v=73PapY*m_8TW`nCGrbCfwsyq7u3d(@H0UWdhF6g1aQxAy*(XfNFw z6F{J>3Zqm>a@bOV!l7)5uhiKh_6XTmo64U&bF0K$#+bGLmEvf1CVz1c>(>*ht{ zz8}VpjzWz^^5IEwaO~hzlf{!wZf+9YPr8la#~!-+S+6+$c|{0lER*ed@`Lg zFASi&LZ$XZD^=?zq3#hry_o#-G=8ApI)HW~s#U1@W@Pd_J)J_4xN|WUZ?R zDQ8zQhU$Qq;_M`fc-9k@2NM1HE1EaDdL;S^Th&Z`nqUGMDhk&@5j5{#(CizV6(;7( zoxkSVIUFJL*|Z=b0PaP#KU*c|qeaF-k`MVuUR$MYV6>ssG$`>&5N8%KO&WE+08N$5 zznsc0H0c=a2oV{`bj=V(tRQah6dFNvbaftZjnUh`4-*wi%<>-&E+5M}&-R{Ep3u~k z6@pL@94CNMQ2alTp#tIPb?K@-_iq?&o8V&vYOEk6M9*s%X;*7tYD$vO%|QH+8Ol~k zja8oJB5zZB9~5MD%Q8J9rK78xMmMNc6#E*y&Kn=pY@?jwcy&yA2Lgv;o*iPp_F99e`DCkxgz8-k)zljXz~sRdWi4C@5SU#ykK&9 zyC5z4_yM`%*ZA+tO3IFRj^;@=5HHgW^l?pVI_bh%GE@ZPJ4V-UPNyW%b~uqfsgi^EWuW?`pOk8wSqhvp zcqpunp+l?aAaEVK@4;=u-s`*h(LEf3Ys@>%r&>s7q;exc^a@p>K6y~GB$U$H_nAK| zx&tM6m)ALWE9m^PM3&iwx`lN5WI0~8lmzXtjz zOT?<5?psj`&V9zFRSyDdWOOmi0oguw)e=PQYW$66Dr8Sv8E+?gqpUiID6`057_jCp-B=sm_kWgI%29|r*{!Q#_d>0!Kd&L-o^V5`02DYw!mwu%as-tgYTf36< zGvq}TK*%S&GD!$2h5V~A|GRc}P}JDRkOyx}WUJnvp~*H1oMXFRL0Sw#F<9!Z!`rnc z74%W!Yet`OJvJkZ7H#oiG4Xc$g+5;@Ta^(guG@vLug%B*!9`RG-b*&T!Njkb=pig< z=P&F2p0N6I_CWx;mfJ>7T*8JwOg~gJ^=T=FlZ}rp|LBE?z3s5KqPXKa8+ZVVfR#)? zSHcqk6TL`oapzQOIqnsw{4Bs_&-1AA`w|8h0r`R?66(PHwx_Xnv(F3C=$OzdMy|2n zy@?9)0zD>9G>BLWZ)U(;a6d>+hms?SG(x$E%^D{TLWVo6q?@WhZGy;-&#kFEeHiYC zre$ZY-hXQj=Fg_An^)>ZFe#1gk?=xTol$u9)%_}(`TlF@wQ2Ve0(_x#M{8f;7mGZ@ zK5W}b8Z~e;Lnn_CCV$LV786eqt~4(iLvUKO%kfG43Z2&Y(4KwK;t5^IsUI)(gelu@ z!S*vh5J;mpm#&yU4p&*KVF0t~G5mb{O*W20SVslrRz{7>_Mhyp7XS6T%ouoKZ>fg4 z!;r@Tyoa>*s$g4kVk2UpU5bK^LrXrw7Reb`NLDd4IPmNK9o#ZdOU5|nLP~M{x#%zn z1E8gw_7QFdBG+2%dVh1k7eet(&Y~AWE?W8Qn$GUcVa zBfq)w!dg6!HR$hjq_ttl3l7mJEOtgg%7$;@XWO$|K`EP=w{LE%tOCEaXowIojU|H2 z-&MRSt~GmObxe@!^=HU$)mt9yEia+?Ljx+rlOOQGCZ#YM>B5dI677CS*sdLzOo%d5j=KDaWI)}dDh%{BKR6{(d?3oKvj1d5$$X_+ zSTr1Te8L6X9YW)BM=YF05Ct~p60#E?V$K1Ea`V}-pOebDqQ z=}Fzo+s=S=*1MKxGmnJGJDfl0KtFKjW;Ea&Y{g`5P#b!BQO@lhHhtlb>soig41CA8 zk(Ub|<36x3tiLDYk~wYwb7D&jCB&Ew7X)vBLDhe5@qd+RWqe%<9V@2k%VA-aJ;AQC zq1LsIl6{ zbg;o>7tg-bc3v(Nu+V!c@iHbFn5*gzmHJ`KDQqV|2kQ7YYCu1~xN2`AbazPDI@xBZ z!x0m}H4LjQpgamDu!(-ta+6>$z-rM%a(&Gfwyr*7IJ-$&>$<>($MyFA0vUQl!P~_*U z;5gCJ+7|pPBWcLOt$@znX^t&U*tcJr&}^s2$)f6oTj(fq9USuV4%!iM+GH?9*wh-B z@ug2X=A%l2t=?e__sP8Rrdx=G>E_hnLi2GiN1X)$1|?Lt_$_1T1rh5%NBM3aq;!&} zG`n*6RAcEHZG%|DugPP%@7ELghAn@oS(ZTwJuKCBe5u_R`AcWvx>}2NKY1vN^>R#q zQ9+AYy9DPHb9bY_B+hxabtP<+sTxSCe(v_XdIN456lDB&Zfi*{5Z!QYYKrW?U|B*O znJ>E}n@adC)m^Vw|JA6zxs!!B0P`~`Ct;%E5VXSB3=>w_CrmNAay=)@@ zZhU+A2XW$ZI8IgcY+>fbeDF!Rg+@F}$axmW99i)3(kLImbKd^9z~;2(X1340+BubW zX$i5Cv$XoOa4&uNQ^1}s^OQK+XQ%8c%P#|V$YQUvk9uUQ5y$$B<)A$n-O^Os*eHQp zCt%rD`Rq?r^Ris%PNZ%EX{pG|;AM0{2_E;rK)p@-(}gO2Z>D=8=nhx+To$HxJd{c0 z`{rK*_C|(W>0s*1K^wGDqlwMPR974Sg>%b?4zJJ!chrEaVhO3o8Ld9Y>y4cR88ZUS zPfpHt`JYJxR2q6L^WK;1J)Rk6QvQpd&))3q8aqz2`Y&%DVAH}BMJ;LoaKtL+Fpz6E zQn0zVJ%+*dBky(O-^!laLKGO=MZ-UaPf$Q!`X1gx=8!2ex#ISpLe8j8Dg5y20TmTa zh1gD|#Mc_g2_c;)!ToQ^Tgg@1bbnK!seO-30p&btFq7Axin&L2&7$?YWzBmDg-B6X z>5TSI@-uiN096_uT%1!m2%ao}d{a(asva%K#IpjIo3Jb6cnHoH1F!6EU}T-%a{X^K zrWQ>VH+Kz$s)y`c=F#+6SzEihR+Qh;zQrNF@2)Wm$(L?_3^s^LiouPJcCod!^?4~h zl9|VpbX9p5VsBr#1s<2%<3pCpuRc(*nm_4g{I-|q_p7eKaX|^qx{TQA%E@!{2dKsr z&w7;5QQnM*vt@LNuI`VL#~Ae2#K0jx{Ku$vMay^D?Bh#lA^-))(k=(DrWwz@YxvbHCg*!_w1ibs zx4DRsGjr(vx$;`Or(wjurfTa>h{ied;_`CK!E}|>bnS$(d)w8ftMBu6FK-1}4h@^Y z)fLq~!3Fo{x(PX4Hynbnx*t{oh$(%Q&& zO~06{EqZ*~{$*=L+ucE_v4CIBm;=DQ38p4g$!&}c`kDeKkC!%>WT^u#Scl67r9Fs* zfMf(_!-k2@rg7)~*RMybcW%zx&b_Ak6q`QeQuhg2(N)cV3bC|I>(4`MbxdUV&xAbd z%Vy{;&!}o%dnGmH;L>uqo%`MW&r@`_LXPRt^>SltYq>NEjg}(YuXq$NROP>zoz>>y zv%FAq=z6=pm}7b`z-er(>BiE14!wG=gFfv%P!KNJRr1pq8cqPbFQHDPJ!VB;F-=yj z7Q=s0&|pg>#R$vZyD92GOg@>kMK}N3_02!#j@B+|(SWXU4C0OnHGa7K%1P z?6j{L_^)QP%Knkd(Sm2(n*2#pLenbhuXGA{)(|fC%y~M}Z`iK5bl%uI}yat!j6OG#0LIzy*9K zw@pHv8At7HP*6>7kI&9Zi-;sWD9SgbKn{xmE^hbgJX3$Z<>4VMU7EDm)CU6>zv7ma zjGEWZO+RqX>VUV{tycWhX&(Qz~g0#yg}O!aZ2rbBWl{CEpnU) z5rkeusT{W@q|D69KZ>XMxVXkz&(IDF(`3t^o3cT=mfWNAx6?75UB{&AKzX*T?EEts zi^*5qc}fePH=9PC@R>HU&Wuiq+5`<1^RV>b4m z^9oc5pPv44;-9I0^q8dXAxREuZpXXeU=S?vw9fveCNWl3`Hf_hk=S zM(=?<bmPaWzRm$~@lHu!JVJzQl?8via;E7bT zAG2`IExbD>!ye$Txs9duBDIGJfZ$9<_~6e*f8-D5rkM$n0Whz*(z744;6*DU^otj6@UMw-~qY%=@T6=~_bA=a_| z-I^DA*qR??8v4LsRNHtvYgNowMu>}>D16ec@}mEp`^9OZ9@V4lW)BN1 zq2^*05{>HJYLK_EeTEIvvv{5@!$63H<~?@XrXODfGWu~1ta?C4EQ_2V@C|kx@Ieg{ zu@e%{XfsC|;k0>l5HXEaC)9E^R+YV?D%Mwig4Ul)b!*XWky zMDSrN7@d&EXL~VCdpE~ha$fsga5EdkCdcv>S^HT|zUQSz z6k;uMVS_Sak0R)JgGi+#sPBxYot(4AjYS8TY~x6LwNUIPYm^VdDE6tye9(e!nw2!P=Isu#`|6J2WYSQGE4FcWp0 z&7;pvFG@bRnx4NLD_eb6bEqU^vDjG8dsj)ba^ua73f^biVz^MIf3Ef=F{VU*#{UKAzrCte5l ziCIIg&Mszszb@AoH8K?R*(@wFN?C5xdyWQI&{I5{4qdsw7yfQ^a_-SOIP<%Phs^l* zOH+HSYdD}G=b@pR4HYzMy{FhJa4D2?9Bm%R`dp*iFaKn~r-mqh{E>QWXHfohWg<)* zT+VxsAIGGbg4f{TRZV>#Ch(be))_9l@LCTpq0SKQN>qA8C6MeG`3DB|myDMqWJk$N z{NX563CUknsCRRe8`mLX8$b@KmX2&F*jaOsyK;>0f_G*`UF1yH@~8hQE7H;oS;rg5d*JvcgP6S#7z7>&i4CsDW@$AeNE7#VK+{M-8>f3(byCVFH@oAe4D})V#GAz%Gz@SsT?}ygG`ZUtM&cmG`c1ObW3%a<+Eh!5+di=MF}`S)Q#$?f zy{5JP&-Zs0lL8A?Lwdvsu;wPcE!Ooiir7z0$Cwe+n&dzk7dNP|_^h-5W-X0eb^peA7T zDpwyxCY54~pEEYkSJ3mAX8a9e9OF5?L@5U})YEL?o#?#?=syyRBYM}2Eofb|ZgdBk zNiJuw@fVqT#WwX#b|zw71nolDVLsEOXivGHScRn!6SzVc$-;q3jcLCLdqQcXMr$n6 zNv;c#ZMQ+tw561;mO(<2Y52Fjkj029pB~&|nemp2oMP~~G^&;U6(^?Ca$Yydy?cT5 z`gkj2Yu@q86FKDhUwh9c7@i`?7SJlX{18YrI zz70sq*{hY3jn07l+h2{Zt>dwqU22bBh5?khOz?6*+L@E?6%gC=v2bI(;&wGPAPX1H zOvJ{;&5e(ThgB)=>+Oy0VMpq48Do#7<-+vzLsL_=WFMe57LehMfQ19e!t{PA4?E}%;lf9n5n$E+S&@;+KIHRAT!0Y9Ov^>_r|RZ#Pc8C zHkb;f+XomNf4`|1qC--UZu6%Hl4SG5TBNs7_C9sd_dhIQVq6py?<3C^UdUX0xxeUM zbJ<@dXv!>ARTi+5V`lTccQ4&B=l5m5$zpc(Ch^Hj`{?`E4M2}XPWqXYxL(VdpJMDP<&L*aP2w6h2#JuBrZ@9%%E@eI68up>LrUv5+VQ`oQQF+Ni$pUx6c?ZnSxSkY3O*&tb3dYeVWL~Hm>0jVjTmu4wJ7HMzkr+u+>pu2SZZ%vGAA_ zKbJgE0X$z;zii6 zu3Xege<%Z5yv%IH$kO*5A?r`>Ah9)oC(~VY#?QdOz<)|MSm0Ti$)G1wpJ#b_IRItr z?d^?>jKnS>&rME#_S?5`l)#n;GT)wnlWG*GkzaM~KYN7ynbv`X;dD~e-3EFfCoOA+ z@JLvL52|*i+Cw$I6eQ!8_?{?WtxSK+_X4qPe}QUN@?*KVIaK;$k zn=kGsqW-qKU)@-bq0jOT*qfuk;Y@~t%v3_8ZRnco1gdLSCF!VA~3Fp71 zZKC=?pq9|v#fwik_{)nYyA)nt&s`5&yzMpS7fwI#rtK{(2i~d-rPeS|{r@h&^{7Aw z_i=B+MKDju(NPfovNRXcXaAVw`Aq%DEW}pcQj2(98KsjtBc$G_&A{g3WPEh&7yaiGw2w49N6Jd>5syahn@zDG7o>K+7b zjhN|?1Kg>uWx8Ls#Z~^S*-v3#`>$vH?=+V84g>)`-yhjk6=pLhS&Cte!PrLmgPkac zc{0IxB}q))?yoG@WMTac{MD0I(?+KVqMM$`zkMv*qn2tnAtiNz48@vkF&LbDQwX4- zr)t&F*0lE*aXVgeTXu_9#JbPcd{j^HX=DQI1;iTom`7K@T#9;iR~%ewrvB-bq;33n zn=j0e7XgB}wjRuZEs<=&woCfoPgg>c66V7O+tzG6j^@S}&Pv=wf;nEnP-O4e=#l3X zzgP1C-#;#RxMvS5|5@lK=y<|&tq-7yd}PHi`KOakeZ*~03}X9V_C+H;i)i;slcz-T zcT-KYUoN;~p`X_isBRf0|DDNV-FHG(-^fQ$*l84PT+i2~z_@6!EaI);k!%U9v{{yp z)3aygH8nL~znUHQmX($H$cF4yeeJTp`ym=Q`&?DEztZ_?=v{Wik<-xT)g^OWs*30^xou`yt)NK(gpqR6ik2an-9h9$sofz^&d{=Uc z_dM_zoy;0e%nkm{!FroE%l4)<$Y-tUtFFFoIj0Xqsg|)$cbnSyo`7!>the#}%Hinz zm>4$tvbgEG{{zn6w0pF|;u2=4&rvb_(F&?U<2Gx!T^p}8(de|07^6P6ghB?F5kszd zDYZbDU1V3|1=UB;)(dU}F=kjG*cc2P5dEYW#ieUa63JB5{NbT^*@B*u<#YuH{JKIlo?AsNQz}W5y~Fufn3MJ==93IuIfHoH zgWO(u)03lrw8=Mr9s0On19KA3iLT)X$9o`)9Kk%v&<+nYcPAl;udivULdZMfmHRpWyP)#Hn1$pmA!P zR%HMBdCariHwKjg?mQVKhYXIn-xj+7f=khHTb(7IQ3v6~ zl=VXa#Q@7JSHa{hVZU{A{bofdz82bs;ep&rV*Vw@*}#h)Z-3@Fem4C_s#dc#gKz!> zCZ(vvyx#YE7gH6aY*7f8vtmlsryvLYG0Y(mKDe10L>r8*@lRLyNQyby5tS_Vn14N9 zZpVzi){uR_WK@I~pNt1{BjtfHKNn!52R;=A*;G=)$`*f%eJBmxxfdo|EhY$m^xmfJ zmj&pbdoY6UAiXFF+gI|4A+V1sA7CdZ*yV~oHYH5^Af<4`KOxqHES*SENona)_0g>p ztV`_A*GG}D;=xt1p*<%jC-!6yzx*2c{%6U_XGIneO8}XlY@k~^`BB5x(v*vwuk{xO zF(z}({ss1xBJHDG;el~a7s)g)H4sSn5%M&LQhEPNR$EOyRC!4ZFC|$>=U}&$u^$Sy z{jBaVX9b+2$4I@8p-%YLu2l@a=hTj8f#z+V58f7Oqt$H(X@GpGWnr@Pt@$Kd7al<& zgZ*+fWbI?%a{l0u%Ua-!ZjPZPaZ68_78X~rPCIT^oJGuzTHa#{k*^&@NI0FU{Oqhm z7ZefvBf@*wzm0AO$=y*^*t!z>+pG5+BmiES2gW#xqvI9=f0;8oSt12 z;Qw_hFUL6-UgS%Xe<;$cNsg1sscFGq-EnJ`V%zrUwdf(5oMMd_;Ak8;`BngHx+k4k zR<6f@-K78!9DLBwCA>t%u&(A2{s2>L=+XBo^IlhS<$I5D8#6tq<@`6S!6%k+Hqd+xP=7z-F1kj95Z=WFt^4%J+)YI4bL|4jOw<7; zgZGxszIxAV6w95dpQlLDfu%ivtpds>0N@Bjd*LnM)%ZT+Xj$qWT^QiiG)wKet~6Vt zWin&JI@`XrX(`zlFS@hn!NmSM{#6IFduL~l1wR1X*ZQ!`{uDAk2`Ya76H7kP+%(Na zlBQP@6r@-0>jO3G4=YTH2w;4m7atyc8m6_y5Oq%*1c-`=*i`5bFLw>iQb)xm$jy-Z|pr3237V88Vfof)2@dJaP+mb*Rd(J%TD8m zIdQ;5BJEl{G9a(o!xpd2- zIFiAGr4*DH4XtJxst)Y!H*9fkL=(W_9^$%via!OT`N`?_-LR}GeB|a=_|%G7QespO z?MO8X3mPY{Fnv5W2MFjXV72`tpp>Jr=yUGQUfh3xBD_Kf>eevAkbj&0<}JqR z3gal0OPZDqE`?v}15BiSI-&qs71UTZ zEL~mm3%7co_LE4x7HZQ*{5|Nmymz;o%&oy434&1?^ zHGaO&{ASHOQs#by)kz!U_`+YJ83o_t2p*bj3(BjKR!m01PzdBp&QyH1o}I32P!{gK zlpP`QQy@&s8wkr8%8TM6fni3EG)=pDK=F{3ks@EWB3D1t zqOYMl60f^g*Gg|4A+V0L5{JOL2Bs_{6Y#=9JMM_7lHl*2mU?oR{rpHnMb4ninibBn z^dSXLRozKle>f@1rp*C}d4%_}PT?t5obQ{?+fveea=|+uRh|Fs0renFYRd<+vVF*Z zt`eHYaCb<7G|@G%1xG~hELKATtG4Rux_5c`Egm{9DlPpIODyOkOM(pf9eCq1VHSTwJ|d$BI}f*@sn+y~l*p9@GyqJ8$et ze9sVS^K;ew+S6d$^7TGeUj$}>J&CP|Fl)~^+(z2@h=Zn%R|RsTHMRE zLBE|_#I{$wuZWJ{zp-jo^2&$8qcKCQe;AuFwWp?ilQ%W{fha>^4mk0>$;Z95hyE~5 zItund3_lSIAz`!-*Qa~*8`pLIL)j-S%@cV_KhiDP^i5@BOC8x>&|BrCbbl{kWl?p5 zlzaO?O!C1=A8!fe`Xe>u(%5B5&^2R07d-?3+^BB4gFg5a7x|b)xU1nAWhVUoK0Ji#A3Od9R zP^+nynLNX$4Fv@ShGXraOf_Izoig^c^@-W3pAKL4q<+mi1Q|9Ch;UMs&dEiS2e>$lt-4E}+oz%`&aVtXoc?|v zX-l6G((P-dgl+f7o-_WYbtUB?vZk=j#4!nn-^Di{Rt9;0#9%=npUh3LxKPXUx%NvX z8}x$v!R>*)mvJx9Z{-ml?LE-v_%ZZ8Zay(6@C~qN1Z&2Ev#k8|N`5SSb~b)@mAf%`8;Mc=e=L{0)b3%%LZ-oCocXi?SQ{|MF$ z9qnzdCdXtPT_KJXoJ>HfM-63OKVAn=vF}fCVs_PncR`D);h(l)yk|h%9up%~(%T(a zwg<PFraaPr0fX%+ktZq!vqYe5T&YOb`GW%EobnDBm5QYfEMpng8Hp)zMW<{LAY{ zFTd2c{~#6u0!F~MwLi00+p!6Zh*M|8<{N#@&@tE#JJ9=z_}k<6<^)Kzu}YhqtZd+F z*X!*6PV+&NYjAL|ot+BlM@&35SY*`q0{_QX_6Jf=|AFA%vS}sXIUd2Y>Z$SDRA*!p zr;2#0WpX8~ah`hhmvRz08;$gE-qe8jl;WOl+^je5H9l1sUgwdgUWJz3-T3$#v@HW$F zb-*%EB;KV6P>scXJ4z&i*#$OE#@d72Sc<>=GaYis=D9B`s-q9RLdJsmO{*rYuNXIk ziZ;NMi0V6i!gT95(PbR8Rf7*95dKlHfh5eQZ_0zyw@Y8sVY%HxO87%6+Mb7-cNX zoj2s8y4(8fK`+>acC@W+&l5cJ#PUk6o5%`*-^Q`I=)|sW%7HH~B~lX7k(kM)$;v#X~W2IK>$yC7^cbI5ayui^a6+>W-Z6FE|>)-Pb=s017rF zG2}>AqxE*)^{d+(&VN_aLsC_l&35d6_lF3>l&8shqI96U2~#}L<%N2_^zVH}UY_@1 zVK zEX!}o0fR~Pd|3u|aFw&pG*Gt1ja3Tb{Q1a*)2jWIO7n?h{a^7x+EPxwz@V5eV6uz#PNY0l7{p504M_7o{H`*{kP$>V42qNa02dJW7h=qL z3IQrE?!230M9|^YRz+uV7UxDh=sk?i9(ErWSSAPHb6|3A(Dvb>e#sBl=}LMgCIKqK zNDS)}0)RXgoWuoy*B~NX%T8@v@Gw)OKXd=Kl54xdJX-so9TvIGaAaxoU^bKmT7|8N z-~pcXzk@|_u@sT6Qcn@)4CLbtC8X^zvWJooT&f}&m=G-t_!GSSBa|*U>t*P^V;1SN z*GEN{<(td$Cx{UBVrpnS(aeR7THz(sMgB)kn-Zc}Vus%75)Z>|51BJdMy*3YgX-k( z%eRbq7*A?!)+$eM(6zszmEPTt>Ycs2FZ=-&l`aO{vy~m_q6F5syBd(#a@7W}9IeTY+#Z9G z!w=xnq9Vs-N~y~?#7O~!l~C+`|9++{prC2TI{?B!5|{e;F}`ig*z|6jwd;>s1w}_) zpx0n36Cu07Ljc#2)V#iF^((lBGz1f zHo6refxKjg{1giurr#FhU^{s51R~tq~^cFajRFt z1_W1{vY*`!N!wcN?@@W)G$at79H>D;Hx}%mucy}=32fu58^I-VV0J)f5LqsH2az^z zN0u(s1^fI&d~ksq33)0ceXBIH(Wh}44^pF|rjAd5inu{)2f(Y|DzTb)Z_SohFoZq1 zI%JVQho&kRHyRa6qF6(=pX9Y_X9`T1-w#g!nna$|{zbUhK@{7Hee{b%Rl~vSxTKpw zmR>p0_7k#C^)(gp4^lqk@>oa8DI=vJ$}wTZ*GBdryGio$S!iO zw8B2kd>O>~4ppE4>TB!y`Bwan+~=0|w1}zuUT8uh{0E%8U?*o%9*Rhjyib(>O6V(% z!6%!NVVvKid<0)A24|6umx2LZFg8zVnn&E6@5k4+wJC-SPO1O_FjD}MlB(q#=@lYk zgTL~cA6uoE3xsesLQHR*MriW?kEX8-i>iCSJ~Is6ozfCYcQb?tNC^@mNOw!;3>|{B zfTVOt3rGkE2qGy+OLuq2yyyA7*Z+Ls3v*rPoW0N9Yp;8)b*tWQGuvPFgmx+?V}v=u zj-SCSsP%$f`5xV@id@dE}XFz{ZH^VnKqF6)}(sv23@jn*$7TAlFrril*ycI;l(eJ=UKQ1mdW*2QACzlAV} zJkAM_PG&guxim2uBbsTSTooh5>8T$#G0V%?l)MvVh%rEcNPAd1D0>BjQe{2nub0|FjL)#aB`AL|m8X=714XzeLps6X6zc?SbTOPoL zgnUDT27kNLzSISdl9~8*u5Ha;a!yvg;q87Xzyw|Kq_^7cx7^>Fp^fW6eWA_0HIeO|wGS+H=&!t_V~b zy>kU-rCE1e^)B(6k4N^#Ihy!Ra-%6D#h@WQ8f}G5d$x5{mBiyV!V=D)=tc2Iso;B< zIO7vo!ho`UJXbX{Ig$y&G5`7z`vi?vT5$y$j1IY0ecJB8$&n}Y`+%O>4jd^7d4_2xL1x(+)6Y!d>lLuTR;6(jarH>*T=Z`0Y z*7ghBJw*RQrq&U0qE6{3l}o2NuE#xqQDGjmV8ym0|MG}@%5TeOx+0f~7>R{8Mf;gp z9MbCtS#oIYpfwgZ(FK-nokGQPYExa=Rzvb=SZ0EJgL^v{tisP3Q^fW zPG3BeKYSXtjsgM4X>3F#@{kMhsDT8;Du;<)1a{wNADL3-n1n zu@55Est9TDz{}(}X2^|PnzOM= zJ%@2(^U1w}BPSy>G=&dS>sw-KG#Ot8VkRX>nGf^mo6;*r>e19|D+in<0ad)1PGx?~ z1`I`4ZZhm_)1y^C%g72YIi%d)3-1^5+NpBq&W`?%Pr+d~Fv?Wk&LpTNV{rfY?B+n#H;|BRpx9Q{cT6YDOB{Sx6jKyr z(g`^VEX;YO6W0pqwY#qr4-3G)*CT#=Na`boT4Ig>=UbZuE*O#Yw&mNM1`YwuAVs8~ zH{&8p^;gcOC(8uTr=ROFMX3 z+60bkeo~mKUL6%<9eV}?u9n_A+4MuZ;Yxy*FgY_n7rgw8pe27$IZCSRLo)MWYM$6=-^Z?#Zjy{+9^n<5(nx$o4ly5u1t|jk4rclF#{}Kmhz{DN{`Xvgo_Mf({x(9yktIcxnVK97~Tcfwm7E?*87{h2ranLeoGBf(&I!Cs!XZChd*`udcc0hX4E z?c}=`Q}OE_bsvzwp`B}-H4a0FI#AcShNR#$dj{k?^7x-tHkIwM z?>y=?u+VW=P+0vTdP!mQ`Bs*a&d?sH+WNlAPOp%DQIQ8+>pd2MPSE%FyNm@*%msYlZ9(n~5ROark;wb5Wd zq04{Xh2%bhYvLy;-o_0gNM1&^#XLgx{=S0)rLtp>W1zp~$mZftP+EO_couviCF_5J zJb#-$2o*mEghVFO4Ek4sg$$GxkUx$fM!$2N2~+^+1n_?Jr!7~H8tdip#6x~)jVsF& z(><7oPCxvgz>1S=>R+-_*IwIOwPf7#G(QPs)YanNmpLqom!pZGNF@BHE=)mShk>tD zRU%ff2+Bc>l^0YVO3JQ5m7MwkHN~V0#PX9YaB8RL6~@^s)6eh-^uFB=@?SM(*vu+< z)KuL2h|Vjfile2=6CIiVLe_tIGn(x`4CX-YTx+0ftgZ<7FaM+z+#Uqav5+huR8Q++ z+ikRF02FSaQ@=|=nTicJJ8T?!(|Y+!Hs-hR6QSyMo?HDd3NCW#3%kUSh!1dP9yD3B zrL(U6o?%RNCcs2DtOOlvdAGG4cZg_-(2@=P)xIBY_}s*swG1>por|^61a^ftca6v> zBH)As{~`V;?Xza!kUjKIW+-g(H{8%B<-kbAKS_wOtt|#rFJ!Rfy?%<9nV9(eD3KSz z@3qize~$_gV`JckiM?M7N!n!Zxx+kLnAp(H);-afIDMjw`M>Ch+UdLtv*6!J!QreI z?E)s6m{hwcQ9MX()DViH0Ueay6q-L%n8Ob-sREYwpbuo6k;0;D5|YIS9ZikR?bqA- z8f|Wj?3DlzQ&q}08N;S==P^|uIYJPtj#j!oeHJ{oJN!uOYN7d0zD|erZnfFN^7j8} z0q%C5Pfoc5$%nG{sQp=lTT*A;zUZPms;|lO6$DA;k7~%h+lyARbU@i>rx2TiPXVmyqO+(jUokXu5H!G=~xj% ze%O)oU0eyj62W@^H7)y(@&VtjBXo!Kq?s4RTU3n>*RA4doHsrBBaci=HqyHPp!gX0 zU1e7EKq2AC{NHr*4HbY~E!wC>{KLGy{8f!bqzhqW!pZ9iAn%0&3FHuHjjO41P5*ny zW*d)w!~RBD!vG?>_Ur?9L7%3krka307Etx3w$b@!tSlL=xs@ScspV5wxM=Qu|LMqI zC$K42a ziJU5SnRY{cudv@9TeiuO@$mcmy;b@#&%XcO8(Hd^qdy}7j*mNPP#Gl*DCdhy`tPk1 zG$3TBpy=|%Ui#p^yz=wM4>|UqxmQ0(n~kcpxPV`qecx7pIpcmG^PwV!$QRtJWT5cu zkgE8mqYu;NkUx6>js`DL8nMgjfH47$&>ZM5GxaTZ;ST-0smL3A$|Lng6rGB^e_ zI4)9{YHxwcGG=NBNgf8LrrQfvtOVXC6_1FfQ>|I4uS88AatGe3k#zGyPD*{EYWqaW zSAYLRjd@WxoJS2smxBF*f&&~-jgr=Wb`-A-?UA) zI-Pzz_%0=XYjJwbi7H{j*IEctxXVot?mXS;LqGM$+C?eQEo`Fr$B^F)(6%;d5ToZu zkVNU!uT)&bcF12jbTl+}znx-~0dwXxNYB_UtF2|Gd4_oWg7L(&NXngCcp;2>A z0(p&W?gw3Ux$Qw;o6T;fw>M@Tm9QkdPh9&x#hF{P0m8P$RXm~ZS#+S{1UXK>%_U^j z0o#0=OZSmOaW7}vtTEjx`12pn+^+umih6h7P>lbUPo^A+HC>DAxL#bqqNz_~GvX>H zTLp17vn3;d&75D>k3F2-U#0>Gmwl@J^O6J_OU&Y3TMm#ldK{)=4%(1C<344O5@kul zzE*^X$=|7meM=}@XDa&2gCBKDo{7kgQv}+_$zcJ3Qx=j8eqvAXN2hd_8+Mn`$SKf` z2FH+}KPMIsvY~YG(58rkFpgj8$!6H$3#w31Wjq;Mta)^`%+A%Xl*q|n5;w4 z2q%Yr=%yA`Y=MkEdhf|58vsL>(s;24k9E+lh#|!< z#_{K{Uggy-RN+Bh+5uf6(CgM zc5p{8;95gb-{s7OjJh3dkXwz**r?Q@ z&--{4&c-hz?`=+I{9EkzDciz-GKaVtGn2@FdDC=|VUw#aUS@*Yt46!pXlfT1mVV8p z(OR|ZYV&6UI{FzLc{<{YpIv8fH4kk@{aFf|!-N>KXpjKKI_fX!Z{IG)!aJ4w$Cq~B z-%7N@n9iUN4ddz+Fxta>YC{MsMW~Ret*zn^RT-th6G`B!zxL}*0scEB6wC!-X9v7@ z%Kh}|w{<;7B*$j;?}_{M%?GVa$zDE6TIuD>+~5h8VG5$L>)lnVG31z9PM3FFcQR+W zT%q^~NQ{GgGC?AaueMm^5i`URiA+|Vm=d+DZ?+oZ9uK!;+V*(eH1K7KH`I+WSwphy z)ss~DBlNQ7r*Keyj-+}PNkjeUHWT5ay)PO@WU)$WVL_Uy2kneU+*w$D+HjoLn2*uh zjAP+FJZPz}s4e&5=k147yg^(>@z^jjMTwZ_oBS$XYoiDo1uVi~K zpfh)oV8OJGzNdtAHd7OKuI3*|Q$2&knFiZ>iN@fqc$wSSlyc;)fhFglO$EZ+tS4up z#=f@&8EdJZnFi%7CHJuhmiP~fMZJA(pu~E zzer0nkVn%le2kW`DDtyR1p`ZcBo{1=ZhLsDtnv^7xZMS1DG+%$q&pK zH#=S=?JPPOPnf?|y>Xp4Pt@MtQGd$Y-}F&*W$$YJ3qPKo|9A=gj{i=xzSsTz2;``I zwh`Zx6S+RQh~kxfdp=k(g78Lplz%Qz;m#Cwx!*fH0@Z{&ygAb*fB?QjWA(T0PoTko zfayy};=A65jZ`h@RbOCmxVG8MO)F2PoLbM8r&d7V@O;KHBiLt36a( z{3wE?NcZ=)er+W^^wGo!eeU-Hy`FD%@n}h-!kPw(3_pt-ETUs zwu83OGKVkl!{(f|p4$-8s~VwKEZ%Kxes`IV;FgrF7V_DiAiV1vsd($@Ep_8tZAe&c zf=XO8L?v!1>ppsOfXe2+L__)?hgSz!Ar#{NrPb_^zmd7FZVV7`BL*=wF3@|ua4_Z4 z8d#qYtT5Q5DzIV2ZFV;reBV6#ERmy1es8YP*Zoq)w(VB}M$|V6gvtbjsN`;{0F5>4 zE%YdLKK}U>Y1w99d+mROqMtm##{Bo`r#sm)Dki8&g-c_)Id3`f>CFdps{JC$BB!jxRa1F-$x;juBpeSxfpwwBWcV!<|HquIUWv zrb{fB&WIcK4i5hD=LhpLHWeC*ZcC#%m#^Jl1mb5(AuU_!3?>`f z4jtoH>HhhgR_bQNF8lG2;kdNjjDeNW7+quB#-0p?69jgyH+JY(+6+`aHi{Jb5IPK` zfTe0@>{+l9aCozDw1_{E76l5+e&;g`Z7EzYtTcnS`Y zlLzQc`sR{a640I*0&~6eBPl!;lf%#MhM)k`5 z)r=eO_aF5t4QE~dLENugEZ)Ug?M{`HmnV-rMzt9nqt=yR9N%biSogJ)F z{{%Vs0s~yyu%@3-0_W*JwLAVJvnB6AtCU~JH)T5=n!N8tzL`%eaK+dS68In)jH6Af z1Bl;So5Tu-7F`ng*~BiArN1Z=VCP@J=F_@E|BJ%jbxZLManbcgOu5TSNYn*bsu;AJ zGWNYRG(Inw`Rx7m>;6zv%H)c`YA_E zisjQ)(+||fJ)XH@=3;#_IW)Qd&ttFNz%NUOT} zes~yIal?)R|D0{gV2dXOr}nNx8)HF30J;v1=8$-H^FO{sw zPe)?80QewgFFl0Bz>HZ9^S>){qPyf(HpC}3mGvtdJ8Ib-L83zR+C8V%BLNV=CQUGu zbVzpJUrJ+49l2%CL1O zOoQpl(C>iB^#JO*s<@1db1TuW94NIJ`X%Z_(!Svd58>apKk*nB?9vY`zu<%u9TW7( zM=4o=e*P<`z>?hCfsxqw_)E|xY{DjW>jz5%!&AcGlmZw4-YUuhGbM0299tBeDz4vdklQ_CSP=T8m?*__ z+E%pb--ss=uuR*6+pUz>KNcf`{;C-W*78<*Vl(jf^b5(&U&Bm#o*x?_h9?QbWa+yT zk&gIpMbJz>3o%xU>(CtiU3P(XRyHlrzkp zM!)efk0z4GlEa6%nUse--~xtd2_8rp42&E~#BwNO>4bf@1|~oghe0uGhdLJ>FTQ*Q zHEpvHipS85W~(EG8F8vW9{q1L$*%I8rei;slA+d!DyIb@%23a0#1i0?MqQdgec%+0miT2vGhx|M8zFghan#~uY7?Na+T1h zTPOYp&5?Rnb6^9MHj$zfkO5$zm%Z64FgO7_2_Yx1zc1cOuNvM?23>k1L|wkluYQpH z*l+XtD95Pq)9vNqVO_S`-op3H_JEaW_M`v0gpP&B%RcyA;_vizfdU|38MHSP?)8F{ z4fm%#?Z%Sc2lMPCY=o1=NDllc(g$$k!f}M1z0)Om-)V~;qw9#1UPZSUBB7gw3t-k$ z;6oBv@R7Lo1VpUxyw)QhV_Q?Tddx=sz@oZmk-{ zi!v?-!)4a%)?xCh(o@Qu7PBr3(g4tQZu0Nk1ohpm?1#o}HNwbNCXWOd5#SJe zK=3c+|2H)!xdRwKht6upJ?36D$dH1a<0bvhIQ+yp8mwd2ji;r#_b^ab@hD|(f@v4Ic%Q7-_%UCz2f7=P z0jHUZfAx^ni2L1)xK(8#6ei%8tosJyb-19;;wg-hWiWEwK%mQ& zt1s<`p)$V83NFj)6+ix3=fnb-E~o$i3kA|C`otYlWvT;zc9LM zpgg7|ax}#7i?2_UzEsGMDYx|hEeek#`)DIVU`F+B*t2*cK4@n%VDb5?C)u-v#?pKk zY-eff%Nlt9w2*_ds;iwDxk zM!|mXKbE20P1pWv7e%oR_goa$VC=u9y~cngiNIyi-w^1m-NO3c>+Ug@x1=e%<=y|a z)-(u5=)`l~bp6?=h?ff;Z0 zQ~@!Mt!6tq-?osGhE1Wr8!vrp^`B(3Dw4HIj*-yU)_P;n}Z7j z42I(k_a=v1KPFwbS@VBGQkZ|V_V@8+HKB!`Jkg5wIW~=X?(j8vszBy(7+mvJnoF7! z<*%o0(;VL#DrhxjuGb_+@RB0k8aVTqHl{$kz6(yN6D;AU!CowIT=A6|T*{JJiI&0$ z6!;#Ue?pNyg6zxh=xkSenj85q+;kQzb|1|)1cnG%h26Tha@2muMfVj)0(8y(5lcm4#i?~SE z`6DCXdgq|?L#_6E`@hpR>-sWHJ8>YWt^Lr!r0FAI`>{e8n&m!+13Y>BSsEidwbOd| zC0V#xx(#|B@4kcZM3YMEa%~Cu+koR|hUy*NzK52@&yc_AgpP&=18jJ3TbjtesE2m7 zg1*DSlRkR?J(76Kxb7vCpAP)V;Zy|D8T!DqNT^A2f<~1Ib&h5v$0FLrg4OUIT<>BY zqD&2+n+j+3zH0{JlJ&b4-ORdSCn5x5ns&%R&JjQIshe!sn^CZZpPql%6Jv%#-yqQu z<^hASBD_p1rD%Gpi*r#hA4=vpGncQ5Ts}+E+qpXeUyf)gWz9Ed)7Olu{m^7#%25P0 zkk(N~lhg|tLOov>oL2@|H*CHBLp`qF@|4Q}R%F7vDc-w~Gb!R|F}@FOY~irp!jk!? z$FDy5m=#*aIya-m+BJBnvR5{z3FlVy)5AkjpysWzhWMSQ_r@Jp?@{ZQD0~YkavN7+ zu6;f1HS!+P_BOFC^7G0=dE<@<_jbug%=+WOmrDhId|FJSDGpG_ z3@Az9iV(GozyztX9+#aD>}+h2k&(yL1c0`x5X^OW@ig%gvHH0>-eYp7#;h z+RF^eCy4qti6r>%qQr^DhC`KmnK?!N`Gl?*$3oDU9%GuSDgQvX$b#s2c`#Ayk7p)` z1@Z$8;dzDi^+_k6t4(^ta_K|=+65frVPWrl;v=JVo+ef~GLRAwjP=ZxBV{#0jF$R8 z8v5|*POV9H{!u5A2d|qbs)^yVzHIN~PZc)yx5uFkl0#n=M=8#@sd^SD2&l+8(9$er zp{=`zfrtJeyROu6A-zMfho*IbuJ9V(XB|cCp@igd`#}o%;>I#k?q;8J7Wj}vrhFY8oqu_5vRg9*67~hr(s}wePzx9(K!elwK*k6E2BtiH@H!T z0s&_Q9U6y5%Ke4uSy^=S^u3ihf62jsvysz<+ozYpnL~)HdKcj36>UE79i5TrSa#mI zJK?_i&}#Tu4~+`!|Klzm$`y5punsXv8za^mZU8V9cq>;seKhv<_AVgId3f#XFZ=_8?pT9YSwI6s^`>&_!1D&T* zq4w4!L4lJTha2+>F22P&-}8Dd#%u&^Ech_GONwFsUt4+@FMh^gNWGVP7#|R3CZb&W3s@A@T7^M?PGa7D!sz+9@lRZ$kL_BOR;)>Woa;S3J)@%uhqtz_Q%?Cz zOU4XAs71tb1&D|;)`jZxj32(v(RBU~gvoc7GzMbV-izm8S%egQpi0&T_=xaIZ47>= zd-JnVC(HM^zf)~0(>vHYZc4ZRO_!jIafVuL42$jSKU>KgedFVahIYk?FT&v#JS!Ei z?_kL@Ah3S$wNJ__*z0iD7X7==ST|qT&6#0=i68bO40r@JwBj>HFu&K_*#ek$eAV27=2RH=D$ zC#rh4@C6BNaIqRfYTW*0SE$Rx7)X@W}&%j$snG~o#U zpB8|TkkW_->GEk`QXey^jjNHka|E@6IK7$bX#ZoY`0}rF6K$N5i;JdpM@%XEKHmw- z=ViV);v%woo+y?-fw6&&n4RL}?3XsC?aD~u4w;sUptSVkBDzP9&`)f;@&Lf+^0~~> zv;qp73md*cfi&bb-9&Y(Q3IXzXLtnqJYa7brBam1Sfc1&*3BI!jYuuCKT8M-x0FCG&usJ6Y0< zrqy2v(dlMy1~iCX7GmK8Ql#eHTi?mDFcgdVL&xK~OK7JN(&S&VC4M0V&O|%^FidDE zmw4QDSiMZ6+Wx@>G}RKKh6V?>5l`*qTpn}SKR?dh*GucPj5t`hQ$O&l@w-Tld4N}#`Pv2D>VF?#8LRTM0y&6wlp<_@%p zJyfvy^#QS$jh(VCMpg)eC_cP_^^?rSyN&Pum*&_QCK%kg=)8}ymIzqdVHv@KNk zc%Nv?Z$kgZ+>a(*;yQQ(lIU>Jk_6o%tjm6Am(qQ2nY{BhS^B$}**0ZyeczS@oKeS; zGl>S8YC{?%HrZ`A&yo*1Z_UN{HaxC*AuHr zf|;J4ndN2T@=VLv>vlrM!|T*szdhN5KdX^nyBS_=(L>VNkP>%xT0kj7*S>$Q*D|0l zlm!D<4>NA$Cm{VVffvZiu<~ZPGcgZ~WBm|IlLt;XQu^#PEHZ$xT|Un|Upx78(piQ9 zNYppRVOhf1mgWrmEb0)XXS|wBR==#wj`-1WogQR1*7)$rC(CvF1g`z8 zfNxDb2A3rL?e{K{CuMooP=&zb4AiR0GAYUCnO+4tAh+})fn76)On&RNbUW+De(mmC zRXG}k9}o*JFdONlNNaMZ@DX4d+ee<%&-^GQKj%Q{3{tq$V~kH&qfUEOhMkb4si}@f z;9?5MvkFEXVrKat-mDW24h>0Pr!7W&Wqj;{3lFB?1AwF~1?rzZcgaRi=YC6k!TNA5 zDJJ%Xv+zXlX=))6vw19gqdSxtCgCJ@wO7VgsGBF%fUDgOX9pWeo z-@dV$LAUjlEBPB`I=<(8VC-$_e^@k|13V8pSyS;h6`31xl@jm`WdFdz>f4A?shYD9IIZpv!W^@4)f*uXAk z5%lBhUOj}p4%}*1oiH>nPtHk`&k5#t6y^s3;}o3I7I0i=u4RAj2w-h|w`=*AfERGE ztZ90JxLV2o&W4eb@-m9w-#&q}2(CR7l+Iqghhy3cMUvp~6|o)J zlfULvU=OjzHRP5)<_9JnLk+(o6CCZ|y|cBQPA3rCEYh|!W%N~A*6e+8as8qZ5UK-Q z69m++$|QhpNEU^ur|V1LKX{j?4tU^@=b@ca!`tQ!}K2zUu zD%qjKw;}xDg*7@ykcHFW@bKHgWuvmu#BQPQi*S-EF*(!O~bvhW1qm zHw@&gembpC{3=G)F3e&j7dJ+9@%Df;TG|Wr8VolxL98*+i};7Fcq$9qk3Z2~J!_cT z-!9t*<5c#i^*5GY>C8^Vf64g;S*cGb#7deKCThhT)ATk?dc9vke=fxVVZHQeHk$RT z{KrT1-H%{cJ=#lBI8}Y9b1(~!CF>SIs;g;yaHRT?@j|v;EA(QRumknRG9D>~4czO# zQ|>V@*MiRy<#h*K?1QXN5?Ff)4OL)TLC?r}YQe(+v*`3uI~E7O(PR=bCQHQ&&GmnH zfq%-i$KpR(6mXE(Gp|2sqr+N%0WHyOl*>AAz=1baq9ZAnotl&2_b9*hV6%$}d*PUT zwaH3CygK#AyIbQ29ujaatY|nIFqW0zckZ;L`wD}1d~|B;SnDQRWp>|;irZ3;Z-M`Q zejJ0$kEOTuxjI^lm4wLcyW4iXn35d7oez=+TXpZ!6z|6puBD_Nu2#M0J@w_nL*n1C zBwrsce5VC+d{&}Q>6UeoU3ds!p!s*J-D1@jtN^1N7}OvW8j^I6;J84ISFK8;PxL6( zm#J_c6tA+2gzUZH^LlFPO6`SdphJR`GU^;cmwh;ncbRL%zeh!Bln9E7PJ!3ll=s?t znju(mNC2a`8G^WYQUsXpsI^KgL?MPaE0|ICI9B2I?PF6jecGxCCucCVq3EB_W*m!@ zuz>NzSWw5<{cQ@^p<4>wnDPAm9)ES9^vQRhu?p{|E>$ManA@WdbX7VP&#i@@_ z#?n zu{?2u2|>Sfd~AluTCxXhCEJ;=WPe`2K=az0{$ncym*xv6l2_dKsvz~!pp%U#0T}n| zMg*twwPjaNdw0SH$Hjks$rK*^_Ghh@wyktQ9T=l;^Tolgn z{oK6{6+j728M!xOu7J!_!uwZ@@PODSK)m;C_Du6k^YwMj{0Bg47;W(~G;i%T)xJTm zQqQ5G^Rg%fBw+>X>*dPUFy%@nK#$7a_BMZAb<^yAbbo(s<(sDyJD{tfOJg&dJttkv zyGpxKuVTWmsQi3qc7$t19rg!{u}}|^5S>)*Pu>asC*Qwpo=jT_KVyT=FL>NQxS8T; z|Gr)3-zb*KC^VJ26`TAQi!z124Q?j0w3^&xzVqv;1-kDkW)Jc9=jr2}A*iv|3#n?; zrk_vIDHHNHu_0rBo((hC(AXxr7Sf-*jA?oSP+0L_w~^ew(s*=N^QxcfdaqG2;RAXU zFVx3pgoU966&$j6e?wM_UZ{<|Rj;H3?^a^uUPYEZLW|_7!LjSieb~;8FjGc!#3>cb zI2!x!ryt(hXmrp-NFd79+OE$0$y#R`I;2IOD7?#jABxDTX)3Rz^M;DIkFK^8FD@8 zVAq9s%4r&4>qwLrNG}sj2Diu+gn5L%$iV7U`Cm;y;LM(@FI_3#zHF^VdgWgF6x^D?%*TY(vpIb<5S}U;%NZ?X?z^900B(d z-zoisA$p}|^gOt>mOuOK1Am0?_Q3i(2xjr$dDj!0$tl)F*T1_RN=(e-*SX^96a3PC zmF@4Xs_S+~T|;%@CRP2i6Ii3(=S@MoO?p#5b)#3{K%{Qy5rXiYHh{I>Bno}7!$CUZ zLGq^G*Gj_Gj5Xwilvsf$6o7!&!}xw-7c8am&Dc$2C6jb|3O&<+QUcl03vyi7pDMt~ zXpzv;3zHjdstDV&o=tbEh-{748ON)jpR4s#alXkq3q7pbuOrsJzqPWkpx>Wh8rV))E{EDXj<5;WoR3nA; zab`{qH8pi&ZIr;l#A%y-Q9iUD%chw}c9CNm&@<%p>3 zQuxHq%sE?m@$a8e{fv>}|1Kk=tWTdL0&hGjCT87M;|_xk{SSQ?Z<#quY^*=U^*U6y z`yDOG^@860f=rR2;o*pEEydDX(rhmqYd=3*9|P5ysVPhVl!=RbZs47^&Gq(q&%5<$ z7Z58M%!QCa1<|6aSOa&dKcUb*??w#FVkmi0-I*lY8?`Q(NBxwfSD=dUvr?EVsXc2P z&ix=K`e87m(E^6cY625rHD1)3A5U~#Xv})J;1B3?d?* z$-Q+cU_QYXKY)JIEJTWhHDTZ2!A8SrMfPmSI+VZB%_I4+U&;M#$WoTw0{x*}Php=Nmh#vkzwT$ED=EQ& zUxM9YziwByinVY%#hcm)%PKx`i;J_w=YD+erl#O{DdTK#JDh{86v!~Fro%0|RX+Y>|@jd`Wsh4oikG}^zF z3fykawv`HM-8{~|UoJd_6sEjCJspw0q?>JX2|UdN%h5D(U@bI^=p~sj&5I$g)~1eJ z_l2n`_OPqg>cD*vrO5_d@rg{^H5KsT6>unO%9V`UHA$MW$9DA)B;fH=S6QIZ{F1Mj zC_lWV3MkdAOcAD*KxjSXTtj`U+xC!{J-f@2)4Nie|d5Ol(a|<(F-9;E}$qezLtOIf_X5qzV@d&}CZv;h4=V+6|=e zhSfTr%V~?!BO4q0-ib5y?Cr%8JXKH+29GbN^Rl-Z3b=Vr5T#Dsk4v0RZrvtTGUz>@ z8r=_N?wZO+jzD>LER;&x69+XDPFWcEpC05rer}j*uZ}TYW95d^D>0Yp8aXU}X=yN= zp&IlSVgtiD(vl(~deu{l7s;~M`iO^3<`|FyBA^pHDi-}-wlH4r>*(lg_L(e2Z1W}A z5I5J^**Ur#A0J<*cy3mDdUg&^n(7E@2~+KNw4e=O>TE_I=IAZ4@6|ftjLjr<08UT8 z?+3T^09G`$M}rU<;F`vONkvO5>A6ETR?mp#A#P~aIkq{6S8iAd?Oa*O=lOi6XF?8x zY`C6CX%?d$;wKfq@c4+?ZICxt(w%3yV44|G`U9x^LizShqvLWGgS4N}DG6|O)hGMV zhq&v@C>ae;^=2x?&lRwf9Z)s%v8%~H(35C;5x^Toj$fx&Vf^=p5%H)$#6ImI9Qv61 zH75Wt3<|9+NMZv=*U|`!uPniC3DD`t2`{9;!0$Y>eUJje!eeS0gB8yvUYD%Ygcmv0 z9xX8|!i*|Gv>5PkimL7C$n8aVN@V~1`SV?~RGV3MKWQI3dr7`B>n;IBra2WKr&*Ak zD%nb(;!GCX-vC%4>jQ63G+Gi6EJlEA`)x0`LtofJU-D#_^m%A`-fjMJ^ecPHCZ;ec z|BJn)CDXE3+Ldl2r%zL#B$y?sGH8#8a(0Jw$WEiI2A9%gKE615}D#H6LUi`txbC;zBts>+QT7zJF+ z*u2C#vS?b6kQN39tc%0GVGc|gq@tNxTqFcA-}-#6E-7g$VPConXSiEBE7Ji1kD$9d zQz(9>l8N_toQv=6+~IfBL+j$jC8=dAr?^Tn_qO*|05lWc}Poc%v3=-?lRdrVz zANVCxWQvOi7ZrJinf)5FcxPC-an%7CVs?x~Sa)_1PgGk#_QLM)SbL$<|1yi7Jpf0e zIwpy4!u~NcR%G)Y_^!S8r~gA~i^;hy;d?@B4jKEviKA1(YEZ&Bq2VXq>#0^8JkA0^8=KvmKN?Du6lOywM)-%J)9-`c?M zt})`dyg0|l$J+}$>36F3HwLYND=RA?>%8gvrpYN&%)fEoK3mLfWvxH?4XAyp^L%=F z|Fc({a1(qA>xv0ku`S=XE-t)))a{^PoSwtkti$4&g{;@X-pn`{-8Kh0N=~!EAF9VW z-(I-fZ=&dwgrZx-w#|nu<4ZuE0Bp zmW1UCyuFuJ3UvknJ286gi7kDvwpAgt#+Y_Nd(64LS6i z)_k%&en{3<73b#%lkSj)U?kaQn_(qQEwE#b@%k2>LK$%Vvypg%x8_5K$qF8&Gfs;u zakZ*)Hd_vRiw?#9H;kA(Lfh<}D$(xke4=UPL%yJq>${$0z)@aG-Mq6!`{JKJFF6$v znj>Q?D>|AWseKlR!gmQ+J^KrSpR9~bT6$^-a(UTo`1(K8b1|4vq_q0$PeCLBLr`Dq zg6AoB6NqWey}U#YjLp2fE{+d_nzYMCKNsDLH+tLLcj?X2@-jt^u_SaC41{iM3exm+ z2u%WGDu?*2v-ksQrm?|Zi8IPMmU&kgtts@=o{pG0)m`9{1Ky=|=#9Ku9u-WkNc;7` zT}P((>bvE4GyjjKvkZ&6`@a5nhHjKrQo2)G7*PQUK|o3bq&o#^hE}8`B_yOpq*F?| zyIT>4ln&-yzrfRT^#0|z1RM%wduYaMC|(B$#|dae3OimGB>sjW!}D-VY<-2 zgHYB$;YGG;GSsc)%er)_z0H6llZVc0r`?ZH$3=6`^TU~MdUoGh&tZ|nzdgc(Pz?(X z%H?&A*&}u$cR-E4;1KeK_@u0zFB-Y!Upb$P zt+;nYB40vN_2Cut?_4f|mpFAAw8z3k!eCIR^x$z`)0s|1ibYY#{ShrAzNCP%fPjGa z8yk4$!?Hdg|e`#AbH}P;INlKAOKe zuBpmD-ekMd;vidM(A+P=V62Us+P{@xvZhXiZZ5{sT~lSMv19N*smRFPA(uiwZ;=bo zhWaB~x}%VN`mB6h^&bV&(5zHRUZx;h8UInzIn{4B3+e)Rn=B!!B*^ zF?whM@1`%kH0{@&9(y-9xXSq&J2{-m4jFL|;MQ8rKdHu&2{iNHtSFhsM4;sGV3SN} zbibv{*xcNQBKW^D^YcG{01qGE#MUu@Qr}39%v6-ta!^u*Q1lNK+|B5q_oiu9YI@(H zhOG5#8VIxYhCwo?PD)BFkV?m4Tm*98Lzin$por?ePY*KPJOTu2kq{HZpC$JvKWOwm%hxQKLZMJ3^x^`;QyDoLmh$tm zru$!h{={@^HGa<7b7o{N@SjqB}_Ny;} zUQEbsjIi&e=6#gv+OPiMIN)aiK!s*g1$IKz+S=TXm5Gp~*S9gN?g+7$Lwo0(etR%P z+PO0mef!N@jaM%+(N;W&P3PE3W*8J4Bd6Gpg{pj!U(7>T#j2kH&QSOeiHmbp;nBA#fBtXKGSjL}6568k9dTV3q*Y6Xx*-XohgTQhgZ*AP6*_G)YcZTLT?v6QGY>9^X{T=S!ivdKzbB9%!ezrYp05B z$(WA*@vOYD8BcbTf-iob1nz_2L24YN(M2SQPz;X)`^L$y2hq|Es9TD)_14U#;tiNF zR(hol&+f$y$;p30HaX9h1QU=EloGQ-5b`eUH}jL#7ewHflzkA`O;5hv*p12V5VjFu zcu_K*@BP-}DD0soRfDW;^}M5Q=JmJ&k)INB!F=L?CFya*yX@Dgq2~j04Ih~dIbXW- zt*SpvcuD>Q#7##C4jnpuIeU*jdG+;6VOQ3qh;*($t_VYzFTN=ZQ-Jy2@=2pw^zK45 z8hh*O)lJFBF&P)LXvPBqO^k zW}lLgK_%yr{&vWF$@^68>T%Ho94SCZ0ve9lo;Xd^p#4%c@80#|;-XiTq?p+0yz9_{ z`<%U$LqnNXp&k8Q3@8Hb@#`Fgb8(q0^vRYIXfnzZo5xb_0-YBZ7kO-K#0=6NJ5^H` z9FNo!-culZR+*)zIFB6qjq83|BVdNhG=IYxcKdRy2+W&nj8~%k6mvHOp!>RcrB8fDrN&S}Alqd1wo6#+^jKe{S zDEhvB`Da2`Fw*Gyj}HZeDG`oZ*wD|O0^v2^bJyqs_uE@YI&DM&?Yd<0+}U&L`~sOd zVlw2m9`i(pXD9rd+6@}Ve-8)j74zbs5Fn(Yq5`VN{V6-Y)dc1NZ8B)D?W4w~l}~IB z3AF&tB|6vrpo<~={FkuXi_S2;GmpuAwpdE5KDh%{Gr}BlIWPK^v>ru83Vyj*xZ>dJ zoQ$eRlXed)I73v9+o=`rGdT_Bn1MvT+6)Kq#OKC-Bv(gs{S?An58{i%l6RgQ(#nA_ z-p|0kA3?B2*^CeWJ6J4_fx~A2d8?7RoT2;iws}R&&-D3YxhKnlojyyz<_8A@l?UJh z>LfuyKs-7>^WN{EY6f9}O>fTj@U*tXd|15w_Rj+u7HrHJR`Bryt^v!jF=Vb>D z1E6}hx3-G@4QvkAKQcdPY)o@4j2*&2P=^W&3)d{V-?iukHRRIu;M+h(+z6sg-SURG z9-lQ*)5EoaKyXxWz7`ceDm9D5KuXXtnV${~LQ;W6L3%6^3 zVaG!%Dk{Fj3;nQ7@729J6i#Wc2qr`(3^Kxo{w^kXUV3kE|ZyXUrwpVV5DwJvFNU-KZs6CP$IGt#%)6hm8Jmw-)%md`XFFE42G zL1mbgl?CGbMeh4$gzcG-N=72x`@UUFF|XSpVXiq~7jM-iDako6p;134PGHZDAyh9s)LQ zS6`za$8;#G##^q~v^oc20>VD1(*LdwYqi>9ZOnJQK*seql2{2a^ z7p3t6h@nM9Qp~2L4p?N5tZ!^2r=+x-@k0=yRgA1@r=#}yg66H4DtY#j$rt(kMt*}i z%nyCr5^aNEJ-DAvHc?ORv3USU9%-|IT-ud8rThyMifTJ_~rho$3FNo@+^qNfbKcREK#e)wH=U26>EJ%WC1 zkUpeCa6H^O-5Ta)>1otij!_u3HA;W_$*u35bfhH3;av^)>~tC`4eU28-nxc(#cKQYHWX;{1e*4Qwruz!cIC*&4;6JrLeRR8B$?6egYz-r{QqFL@m)-8Cz0RM*iK*Tis3pbK zha|su8-7|o5vL_t5G**yll2y6T=qjwE^Ps6eTydj>x9h(mnkzOMa$?KHweb$;poVK zReM^bpPNGIKQquI$<>35v*0B=>@-`FchyG1gVIYG$?4co{{=Cm85g&7b}@xMZ#?DW z;Q@fj@#(2!^UcLwhbGU1?HScop+n!HL$A%_fTpIIkPyoZ-;-iTU+&mkX8y)M&W43r zv0yF^#b`9GyxIi=kgro)>zW;{h40_j)zxWd>y>D!hvu_c6}J1wKCR(4##SdldH`&{V;g_)C2ivLIz64f?O8zTl{F4A9Yvzm7@jGirUfAp z(EaGlHBc)#<6EX8aamu2a zxpvb1=SgCG%QG_EM07@V$)&1J=Y?}K2P_lQkmb=R+ML#G7C*+!I)6o{G3OcUi`Y0$ zj+fYK6EA10@A0;HB|=9hCtrv}!oQrKdvcnSVk#?t7_iX1_S2-K?aVZ=$VEC2Cf@ln z6Kgf8#_sV^=tf;Lag{=vME7fTW%Df#t*2D%g4Y^K&|@MsNC^pv6M9!Y1~^81)GQ{&M~9fGfL@A&1PaB*?fS(m zLW4Ln`@atb%Ei*z8ZXHCtb$2JleGk6X14D8a;a$|NCxBbD3zh@=gxxwwcdGF$cqs_ zD?3yRqX!~Xg+ZpCvh50O)m$B)g4q?9-FiBLk( zwCG*>PolUX(2lzl;iI7y{r6bGlUwZTp-hWoZMkNaLl286IB|k8jWt$Br<@^;{T=xF z(;#y5BxMby@2Xdfe{#v?;>GW7pF)`<@t;X0>7Gu~D1yI^&Rvy0{Wf)=j3!5 zr{$J^+#*M~q0AeruHz}wwh8@W!{R})JK%ZlilV<>6Kfio8`I=Vu&}fMEo!m$oQR}8 zF?`Lli6OH~kBIPhFjCx9$f*v}CJM5++n>=osjpKsfo*hxSKYXuq9IZQc|0S^k&gA2fFQqMH=-&#ZcWuCsy;;|YBAjcOQ^ zo?)!GjIsH%d1l&qa^7NmGE%7Ele~USjOW)(Td}G)(He#0V7T^~c#s*?agB`+(u6l} zTk=ruJmt*BmCl&h{5EFNG<3uXDN@&CCg3pg_0+(phuG(8GT13GxLDs86*|zEYTz@i zRx$gSA<{paTe5W|yXJl3GdFsd>y-HoBSLUbdg$;fBm_$&MYA#WrYELan+;YvfQj44 z$(X|mRUi86sXt5i6djU}@$3b{;=T{+zj1P{;+}B)M~&YNyoigm%OA>)3&KVW zww^b-_X&-*${p>h^e41~RKg@C4!2yCw(W0>mJf$2;eTF;s&gegOA~)BmN3)Db#N|R z6(>iEsk23OFschXDE&s-(g_knHoif%uv(mtvv%{@3|aOBrG1gS7@6w)F?C@^=VmyN zOtU4)PGF%Krk*tx)}MAbhnVy4Q6otrU~WXv_6Hj0oOl_3DBRMcxnMGtEy<( z++g$yYyQw<6x)|)3ht7bqI1eF8!)8%S5s+({Z8sQeJR9r{dGfR0F?qyjlNCis^&A>rT8i#8X_NVG3bVsQZnDi$LW#<EkP;0*MCmHQHG0O-n8@?{`^;MUd!v;`)GRUB> zw%oV(eEn@~Y=DOmlro^(o9mOkcwVK!i51XwzSq*Sy}doctPn;2;G*{<^CJw5Ce&-H z02I;D@r3PtPRzD(+Z1B~Yz=uifx(ALOsu8`w+~+HoqR5`@SJWKC$+qjlhV6jjg`}N z@c?WL38jR1P_p!6!B@!~?i*v{5LS)#`kgnsV5gRt1AFxF+KdnYP6_YXtB%98sMH0< z?+0?PqfFlkMSPS!{}WeD+M)*|+-s+7;e0jJcUUs>u6Sqa#($1P&B(^*>?WfV!=7OH zn4tj;Q|vk)6M%8mOlG%AcB=QRc39N<=(xyn(-_T8=2Eom`>V@KHg0`gG)NRACVh(6 zKWZqF+M}s2Yd*onxOjx~`>}5fBZYkvbOQgo5 zKul6OFzqnSU)JsPojZJDH<+pVTf6+jhY#TAnC7aI5<|t2?;qMR1KVcMXG0B%kQs1% z8+Y^HkZAs2Z{PjMhRovul^{L$Zji>XLk*~TtMntkbf5Z?Z=Rl<3=Rx2NINY@g3+Lu zn3%Y@E?2_hL3IsS{w56mkB9!U0@~lTsvTy81SQUmnvZ#h4zVvT3j8VBx=ml@ae*K& zq1aewz7gF)8bxDib2rO<)(9R_Iv3|Z-M6?7^0kyKSodW8Wvd@fL};BC$>+_Qt zpB)N2R(p59S(7t`G85kvk=`=k`xcKj;$v!|Fw57qovyKEr;pfOAmOY=3fbaTn85Z} zbFa0XWD4AaU(*faNPbP$r)(-kar3-7e;A8}c$GfbV>t^~?4YI@#pu4{WcUd&xe7rG zx-eR_!t%4qPw+&+HBVaPYpqPuKp*5xw6Q%}p$r+{A_3HrV1f9LF)_zS=FVSk&JYP2 zt{;_Xg4I3-AA$uav;qoTF}kt)-|htT8@VaAxkSC}S#GKWN=W<_85yG5n3aE4HhOL> z0vVc&$Vj2z8ltKD*Sxh|1pZQl4S#>;q1f1Os{OO2E`W{o zkM(2Du5p#m{pjATM{v}KB(fsU*XxX8@%rKmiXOzq)aza z^1X6v>nFRC(iNLfXjZ(BpC9bL$+)V1-;{QI3 zSN$4Q%dr8wB!q-ldv&NU90x(jrxM~KT1DCqmP)3;Bfb;H-{5pP_!<227m!mgRc(Rt z&B#VHNCWTbb9JudaoHk%^;YZ9Bg26qLPVfhr%mJ^EEnQd6LpQvOTYZFo+4{;JrT9g zL#MXiUESTC0m-Um-^9^}``35md>54WU+C9oaEf%_b*1O~fVYhQ1co*`o@&`gtHg+- z&wla0+Z1;tkyS0;*@5=Cn2U|`(C81|H~O-jME;jlr_u+@*Ccx&jzfBQ(c8DK=j1&- zqZHxKK+nmq3|(+U783yFM0!`jdd|BNC}3n*_{+l!B(+?Zx(Hy8xDifPcfNj{011e+ zIM($zimcW>bv}Ey9UPI1D+(dW*L#y<&4@6oxVrt{DAKXTbfAQr@G76(1btRT< z8EICUc8^a^Hv5jhg{#Z9j0;p^GV;?xGNeLPKdaB%-YNR9%)CBw)fT+o<7#HC;fnh<5|mL+8-XlTC=lGA|_;(P$s<# zk&O}5SC)ZF6muu-b{*GbYXaQhs#F zWh{w)#KztBJY~IpYE>qx2zyIkE(!4qo8^cU%*?GOV z;-&kU;|v8MiObL-R{}oD=k@Dbs9S}9B4_cD@}4IArb^SX)D_z-bRGHXRL07X!T&^~ zAo);y1lV@~wF|Sv2STnG@b+_87*Y_>KMJ9t=`%GYlK}TQv>2TJNoC}-A3`N+KVO@I zC24ri$+u8Wv`4X$k1>5kXa46!Yfl{eu^_e?K;E7_Cx4QTVw&ox5T&T0fMFeUJj;*c zq%8H!`!2ur_K|}1=f5RF7rag3u7;(&Uq;A%v)}YtDHz+dp%RD>&}0x@HXXo<~~$Qa>@oMVATe>W@xkAwAVX1mxhKQ1<*D z&AX7<`kWuU7%b0Or{Ag7=_2_?>_kII|6@MGUe{Juw%1W%=Gs)%*VY2?k)wBc^zjbP zrrniy`sXBJ*L@7V>(S%14n>TowqNfgQa->Kt4MXbeT2_kbIaTcdf?K@h}+OaFEhPs zPk;O@otP>WXrriOuU8*v?>iAbCpXulc~fBOrBnrnz42VjL-LXS=ka4A;Uq(Rdx@b~ zoTj@Shtqesc6kF5OMZ`zUL75cv8&O0{FR749QpWBDYx8)fi63>hlZJn8;dK{bsbw$ z^}%he)XK4Fl@gux85LIcHL+1CEFNXwjm`YbJ5}P-DFg8eZM)^aa_gU!y`52kkU|WI9Se|OrF3v+F-d+glj=Q&=9RX_b&!6B~Df!M`nQOTr z)LNXOP}RdsFJe>HJcf&8W+sWNZ^CEAB06L_*y^fy*&Vtq5~sCY5-9qW2-m1fwyge0 z!OlBbXCs21dj)o)4<82#H`UfoPfb~>sOS?Tcaa@Cnztco(LdJ+Kl6>3#!#ua_RfPk zTh^ zsFg5s8wI-ekDnAUSsw>n)bP=MF2ZsMvSjS3&WxQKQ@ycsg>qkF6Uj%{sJ{JyUjI-x zAFghvUTRK&l`rHtc_?kF8N?Un`xEaF>lganiz`L`##%%bbavoAbQkUCP6R(%tM+w$0PZYY35MGW{VdXi)(| zeE(0>imR75$- z&nlKV>Ob>t(@78G#EC1oKS-_VpR6R<1Kne?uw0Y;JPfX-Vht{=Tn*5b00gtbl0D?z zF!|`%Sa$UjMK*2b0$$I%FIHmKPOMZh4uZNN0E(3mFHX_ zyZ7Y5e51FR*+P{t5jm0#3(2yo+rJqp?%zFfVz~w%PlnsMA}n~2a(T%J#bqukM!Moc zDrBu~G7SM_9p@~Wb!S7yO*9>Do(Rlzq4BrJZeU21Cuq&bHWWFdX(bMTA@v4)m%KJ| zlk)P|=60(65MMtve`>f(6w59eieLK1(H$++Cxwi@(0Y+xd+>2Ho5YAc@|W2T^IY*@ ze?RT1N0mNj68KUZabcyS1dUrVo13ZFII4oYA5Av2R<~Gb4-RhA@ideJ{sFVm3PY-_?tm#Uy{W5Y=tD(h2TAA*%NO z)BSO)q&Z!i`>){8=yS#gPP&|l6cGmI+R@4o9f3g8skQX*CEO~h=@)t`Kf(zr??C)* zf&k$I3W{T=27aIco@a3x$Zosys# z$0oz6{RNIp&V=LVYB-zfgoHOZkcxJOUf1$8c4^>i^Ds-2foQiW)2;R^F zxt~_0ch?+oNsszQMn(YlGHpLw(`?!mC0+b*|I%WPXZ;?3$=C->g-|-};Oid_ILQ6R z%Ya(S0Cj>?IagABp3-}bEswl!I<3M3e1OXWa>_D+Mf6o^OLOxhMA7_FSWZ{XkmX?7 zOr>?4*7LvVsDwUq9}k(!?Fz8Hduu>!>FA)3Urj{?mnmnw^3J+tyu!f*=dj7+!8+9Q z4w>*1iIp-3BO~f3BS+(Q`D6)7e#P3n3Cg*Q99S^Z0^XRQpzGOHCc#EoMb6xJ!7&>0 zf>Ts-D$fRWB`~Q43Qy3cxf;ut@7Xlevd8bKSk|L=hniD;D_YF2K+cOS{j%fNtycn5 zRR1d@+RFEyn^38Bc%3AW?$!kb<9{-A?yxxj&>|wTA8xdg*sR!QR^4YL$%&w9d7>+} z@%KI9KY%{G=>2A_?v*WF(XM{*wk=#aH&(C}{^L>J=if^0 z=I=FYscUT<{*)VoNSJq@uhMSuHinL#bh+y)H6OabY}jS(yYje;qOiJ6Wa>hL63UtH z5VRy!2h34rN-1(CB_{6ah1Z_~waTVycE`QZ(0?u2(&5KWH2@cf1_r8U?TKBSkV$ZH zS5bWCj;pbs==JVX>F5=7?V`Tuvu1@K4x%qL<0|}?Cu}D)>i#4JYH%(aHo)xB2>*tL zpH-1;=W^YO*H6>VD|&fvm%P=Ib>@Te$oBGGScQ$hX%~szQN4lz0XqOcDZ9llvN7%{ z8!=B#IJM>>$wmb7NXzvb=Dz_fF>&8d%ZPyZh|SGhmF-!GP`3fnx`4VXMl%?wXDk#H zV<1|4vWQs3Xr<-NQ<7WY{zwAV}C143?!PEmkpOWTPL*7y?-*ll#RUQOo&5$}NxwvA2BywhD z&`NXPpB=^#3anVV2hu~QzSl=9X)B@u>8Qr51Ld0egV2`%^)EB!zkfIG^v0}Ck&$Vp9cpkEOxgO?X>ldNeRza{c)lPm zMEill{P$p29gotrf{N;3=MBcHxjN!r^r-K^w3|My!R@jZ5~W;?Lh^Veb1zcNpMWa@ ze*CgL)tkcdZxc4KmW>YKvnO=Lj;*);m}9b(L77^q7hSD$rZSM$vugfjoK4{ST6Usf zPM3kjpFHpUiN2k)=p81^c3h4}u}sBJg^*_Kp~kv^MlTWAt}t2-LwDE;4LyW`|G4crhZ{1JtPr7z1AO zwfq}nIxAU<=c~@>UFUS{2w$V!HD}#<<8JHAx^YFu<4o_P9h?sS6iK;nb0qa;n*5L+ z0$2r*YXSC=ptQRDGsw~Ju-I}aeXDYA$y;BMQ*T&IJoq~uR@q~CZ0rNZm^Jpp2TgCrQ{!DK{fH)I8$IwLYDIej zp|EVHt*0?`j@N=&&Rlz({g#ZI@vB#%jW^d(8St7SffC^7tf zKf?ShM7It%V*iK`0^a}wKAeZ(kClDE)PsLFWgrxFp8xFgfv-OxUO?YpQ*#Ok@kn_L z*)#>5+i0X7U$Y{v+6b_7KAn(lj&ciAE9f)oyJDv`07Hyq-8z2K?y zqZ6FZDR{!}hG2K)@e`3qd>Pvyuif8A{HWbH2#@vY{*ou(i(tH})7{L#N&RBEc+1K+ z9}WR@K~geBf#10T!LsL`TJ8M$Nn2AyZTb39!u?t9TPfbcq_ki){BdG5R%!XsYuhr* z#TbZ@!vB9pM%a%+o))A*m~9w`amGG$;mD_98q+NEAB`7k zwzaj*mVVfiF45w;e}@SABqMg~>B!U+H|AWqdEf8R)~)YLvv_l0CiM9kJ3jL*yfmGgy`Cn~%`k9($UaKGcSQ&VGLCElb_JXP*Lki6xWJS-$4kjD-ZUDXN|!AB9k&6S zJr*3Ak4BY&cXGjjpNGe8si|?nAw%4`^{@dzD*!EF#Qi$4={ocvYz*uOmCGN4VNci) zJ-F_CoV~N_Wl^bl9X%)o*wzPA0~5%x@;{DAT@wy(^&q=zSi_6OaR|E;LI- z-ingfS$b>&$GoxG3; z8COB#7^exvFJ0LA@gP2`-c?iOrDvda&RhGAB>4r{D3?0B?r-9#holfSk z0VvPh%%gc%eurrRpR2Pnj)?B~bR|g@UNod%KO{W_$OvF}Nvm+FgG1?E|4u^7B%-VJ zrhT5wfAsbEPrXw8qN)@?UWI_Sf-i}LP7)w80$?^YHYO}2^xJcBBwHaje#iZ#Wy|Y` zkk`{zA}IsFIx#x?og*ALLSRVPp)UXeIl^Nb@y9#Go|9)`wtRwBeR^U`AHae;Tn#~m z12FfsXP`p@JrdtXGw~0($AszUz3CZO3^(3GB!p3kCW};9g&Y`kaH`Z{sn6H``&6{l zL1sU=hPlPVRuP`%0~v>ye>$AEKmF-3=+&hQ2q(^5jnA;GAJ|#OQZEk-{A=}z)gE7& z@Dh%qJ(n$b^40!RjP(oICZ^6${K<2&V}`Ch_3qlpB6_vm`fI>yn$r78Q6k`|$wb(! zDGh5K22FtvY+Y+A{_eSdQ^t}Aw|XNo9IIP|3~IlH57M)xC>b50Lj8Bf*g!B$4D*u# zL+$O!myR9F{9HH)%7u+Lff{;vm(26p?j|NKPR3RyziC<4w4i0EwgSpq;-1<%9!M?u zsFB#W`YfL;^cDmd0{g{=^QtMsot+&i;At8iy-h41$b|T6=S`li;!gA}9IugC$T3(eyh2!O6&Apr@boBx?H?CrUl8&6fl~NkBFaf5`$w zSjqq!1pFQirz$r~4mBI`DTX`it&gLFaI6Sgc6SOpgv&|J(pW~JFzWvze}f(+?QIZX zFJtgDoNStA+#C&NoF{+0>u|)C(05-bvS3E~?fP&N2w_|MW0oxZomq~?xFxWyygO$< zB6!KNTq@7xl4+pPnjUs%$>CH3aYs)wG{XjSU66iQ3+{R2kN+Sx<9a3o3pwQb*Y!ew z;7iGmzmkwZqVu>`mZK88OnY-Wism_CHAN7y%r2d{nt^XxLtg|kx%Of)vJb8WWAy0n zR83E#Az-}SX4mTkwadpmJEO|*1-O38?LDe?cuY1>dE4ZklM*15bM#VlX$^2&lmcYi zQ0d;p#n7x>xZ3l1PSRvqjo$*{Iq`&<8in8pbc!gr7DxhbLoyx@mG*qmd8rO5sj0`( z{;z+bErEq~Rs6f~&$}O!tD3HX-vkF2nWOl={4tWnDw4I=p(;8mpSPZ~cT{(g#ZbWf;!@sWkkso&{hE`WGCbqlrX-)xM6QD1v|j!!y2AD`%* zNPE*cdY`?3BqQIl2|G#Rx38uSY5C*&Jd*81;|A7T>*jB+-!^#ek6v9}0UwmUO`Sm^ zi6_L7pd{un4}k?MS^C9^0~T~$diwfsq)8b^E)fvC0bDUS*jtmeB0l<^=>x6tkBWCT z1G6{~DfQqN?Dgf0_t4RyQrZ69+Rn_kJu6lTcIY_x&Y zRHY9|YKf(5Xjos(^VZ(l{b1rfnx7yCA7L9`1{Lp_zxJ9XE^iS365LJEqYO^3uaVghAAbV)7@i zWefycoV94GkZvaM0j8*)cN^;JdUQ!G{t}N;fpeh9;jQ+#7{JsvlVs@iw0GCGDkY*5 zSPTK8`(GHq-=*dZK{kprzdrvz9~Hto;E;#m5M;H954Ane!A?dLM@lN zG$B}jf4^CUo}PiWi(k*5t>b#yMVtG+%^+9k83ao0`0;kcS&1loH}V?Q9RXs$cIw4jOMLRTe2R7@fp-Y*bjwzY|7*5 zxPLL<>-6yZ{xkkA%LlYzq!|C}<1$;%v)GM$rrTgeXF7^b+zC+;y1ZaBuVr&LOqi#% zv=`~AP(B2n?wYJI*f-vPn{8yS_S!6d98>uo{OL(B8d-a6zylG)!4(~L@1Db<8MxLf zXk#?G6HXg8Ja^u{pD#;Rhzs?8i@1H$Qy6%PF-f5N(LkN_C)dwO#A}Pjm4nqjz{5wg zjLvdCjZGcMBZqe@G?1znY7vCM{bGN7_deUp^2&BT-mJ3778DcHDVYK%v?2~Fb7Nzu z)#^SccMOSHmopnXJGecSa}O>TPlbivwHRcPei^Y6kCKv>HYl3-YI%1 znl3CS8XFUcklGZ^$gv-R0qZ`Uy5(#pK3HrsOYr#93^h>RfuiKORy#BL!=|{BHY1$C zUa`<&eI_HKjp%nL+q9l!V z?<-8%Qm{!yIHJ#@lcbFtb{pE`EcO>CDae-*dQ{1JozejtzN=hGa#Uf#)1tDm>Ez5n zT90|d?s;={4uZH9ge+CIX$Wqw0b^MAPRP8qL7mI$-mf+;ab?KNwJwZa#{E}o2)E96 z2>Fd4_cfHHBoZ@(+BcQJJsz^~-#zt1gD{3KTVCKx1LnHm1FW`ZmURXe5l?HH4YE`) zGcg@HOq{K(Vg$k6b#ZwK%WU>v{`&)`^)9S)dUO=jG;ky>ewx;MNUQr%>j!2`f*p-@ zwHMcQfA?X?S6jx3_pG6Rm(^$s(UM?bR=-z31?%#)N`aVIX?2ZJQ{|%!>9#Lut7(L{ z{F_8QsUoHkdHNGgOKRqW4E%ro6(AFSzi%V0=k>hb>Z-t+GqvwioDCg~&Ep=PO&DPh7DCjKLGa3}tl2cNmg{7`@zl87qUxO=ie{qv6Q? z16VkgV$e!gbdfG_8Of!|`rj;i?-ozk%nIwd*mXGv@8!M$_;=@7u5uDFgA8pj38Yn& zpkG{Vi~0@%ZmGG+@#WqDF}AiAjDh}m8fK}-P}=balre*EawC?g{Bsn7CNm)k3` zq`qG~0zCcX;(~%@m6bVgQh+FguLYBG5is6h-`sGs52q`FEq9pyf9%v^TotxAes5SR zVRTc1lflKrqiPlRIhPo}B2YJzV!0&sd%RiMqSRu3PH!=%v5}Rs6AUZ6kfbWRhm8+3tj)jh4vw>wO9~brKZ^;R-Hi=FUaos8ev_BilJrpNQ?|C zZdD3ibr9y7HPN?qD{WnO7KJ|B>CDF$0Nd}1qI#ZB7(>S<^7HZb)}(HUr=xlskWpLpQDn4I=_`9#Sr3<}qE_qx zTW)5CiA+#pJ(pbPJ`qbD0I@Dy3Bt)LWx85#H!p9BU;bMXnd2E465tZG(tX@_zfTE< zCwe4ciw)ry{mgd|z8BJpi3=Wz%%A4i3?yR*g$5$CTS^5~FNdz5Of1~JDCT0;WM|54M*Cts*&a_j<;;8R;)sGBh znk#F?rGAj4h zzM5#Ci?EJgdk@jl>bn|pD^sIq zh4|fJDwqEu^X5By%!d>(a@k=~!r&3?2$%qIz%;T)3#-PvFBl4svvoecvp<>XE->nt zO@3y9GvmO;&SZn7?z5;Q^lGYug6Q@|ss+~Jms($-sm-R01(WEO+^#wMK7U}ncXc=< zd$t_ZC;qE5a06|0;^^^V|T>Er`)Het*f&d&v-syXRd3_0#!a^XJo{HT%LEP zwRCbCK5X!6T(qeI`5Q5Pt1J|!zW#Q0-c{NQRj$&h1Ak{KP+_vt$pfperrciTYjBc8 z6W62wz<^Gw)3$2!gl>iXW;J;4`p4e};iSG-Kiuv8{F-!m=pT4h8t^rr%-RwV90K`&LPS=E&yt{bC=Mi;+FBkvk}U0b6w-hlvo zjNiFuJpFt57u~o|zkLzYl;nOEwTeM{d{y8e^p(ujFSHlm>IA;cB^U%BSMcGLe(Dt_ zZK|T}y;xDA=tBSo*9_2x)>+hjUuZV*O}Ajp-PENGsi2+L(|F=#xsd7+7&` zC;DK>l@25QJ+nuwe3pZvU6uJ>+SaRzOd}! zjS8ETgoK2cSaWG9qmkK!%@a1p{#BRnTTkzLRm{X+G5GV^U%FAVkzKES(rEv-T+-FT zmWT}=B{&nY!+InR?&_(pl>5~c!xhZ+6->QIi#5(NLU8cjkzwe|B4!`rV;BooQZ-~m zgOTG;-C@iu{P0J!Q`*P2F#j9$MNl)?{KUWDHK+1SbsabIS}8WV@Y~u6m12!!{Z?^Y zQ2-vn`ubtmxQX``VeJzoL3Va_GHn6~)IbnemU8mvg&USR?0I7RgtImo0~?PNIg=pS z4JTUmZ-xQYat-|@2jn9IW<7xc0haWaC+4hjFME^Rw;@BW$3a&se>uEXMJ<$c6vDlk zeV>c{MssH2!QyA$06xLX>tZfceQ}zGS8hWl$bOI=yzepNgn!7hRar>gam) zh;kAi5ebQFXTD{g(#*ltl@D8Lo#!E#BpVb=ZH^x8{fSefmwdCH?!C*)!$#+X` zxX?s}qL&sljS7v_?umkZ#$OLlEjjIXkGre>L@Ooe}TD_+Wgic!mi!d3}7AABlf`i!st4-(=lb=xzhW{1 zS^mlw!_?GtvdmfW(OQ`XVpY3En_7;9aRAM=+>fCEEi39$k$PXQNXLo)%E%)&7X8A9 zvv0)%&i%&OrRHQ_`!IyHqX?7FZy@KhcFTbzN9{Q z2u1;M`D}*Dg8%h}8%+SoI>nfkh@t=Wabck~Bq%KnYUF31B@>3Izz-00n8a`7H}zxj z1(#~~Q$SG?@HYVDforv#bg$UaukX}%$dy&cNMGNDu4cpz*GQnV+L2*s)g_`Vd85#) zvB~#x8bs4rT3UXc(65-W5lI14lms0^;0og+$8XvNLWP|11Ix64`DTywDJzk2;U$N` zsEc!&{{&>VOxp2zENA{6Ct$GAyd@d;82#LkNR( zNw&AR*oJZl2%!_mdyIF87?X z&)#d@>kf8FMH?&VNQFB67Be45k&Sheng529g{~6hOd98UL`o;jEd4A?o9~mcuK+X3 zc0X}oK)=B2{A3?EDFFSuUj{D@69Q;h$!_}Jmrw{`K^gON{y&dwVB$tdNc5k__(>%b zaC5(;#0KB-@Yv10Jm<1j(B%_0*tKZiMssip_1QYv+8zK?*XXLK>p&?%(!4M>n>oj|<)0zv!Xx->zW^u?lP)YvAt_S-*H2me8$oY^+ zu8}x9L*7?H6OZpC&r+p**DCVrR@jWQ=Vm>3I=RlQ-E861@VLcARSEg3H9_%i7)tL} z9Fh{a@6xkFZ_4+0NAL<|bbmI__9TjkcaXElf@oC3Bn66An~JjEWY)c2)4q*?OWg@z z(4ff^-}5AZ^~B~CNBFH`!4Udu*Jzd07AhB{@y^e$fAU-~uXTR{9OeMx0D`^s1c0CG zz5N?XJF{&BZoxv~>mZF)lZP`T?lw?0>D=>vbNIb>q0U@5@lx6ZO2f(%G%|qVV%j2u zjPOGpz3uKna4p*HnpW4Z?=1_`XwU1+`9V+cu@20+To}uT{AZ?ZkTq;SLt%47g+k8t;vity2K885f;2S$x*ZQMT~otS~Opw=bCvdzbWzTw;%%*i8M*{-#dt-&3It4eZv$_KgvJH8Fb&!SZ|(CK9eIptTGE zP;ZDUH@i}INyATlY6#B%I?ofkJry>^6c1~$TG_6_xIoFjRO2x2$AR< z*ajZW0Kd`(3tkz)9yz4|F5akmlENWhwDwW6`iQC^hoyPz7uASV(^S=uqhIi1q$Ts) zPak}~<;84wxH%1d)qh))@F_K#DU{A3&&-fL4v)F2l*PvAvitX8J60$^#=&eF=pd9h z^_%3ckeltxXBU=IkEDc++WwCVK+aa&ka=CpejB~2IucFV`c@30yN(rC?(aDJ@oD*) z)Nh=bk}(WBhubNXYjRs4v~~s+ezN9W_ZMScFqA&NB^eJ7PYCAX;-aak$-R~%1fak` zB|C&%^HauJS%~6S!x!5@ z;U1w%pDQZ#1iBn@@3l(Ymp@#hnrxMd!zsYlbr~<)_YfO=KWRcpQ4vCz?X?nR_86jJ z9G<)1>8z225Z1WJ`>_RQ_vBvT8V}@?yKN}*G8FL*LLG7Bd{*NB^HcIWe2_rmE!o4) zTRbanb7>kka`p><W2W#q$zm_+JJuZu??&rN9c zhbiJ%77w1C1bu{_;Xczqu? zCR(zsW)C%%xYIZN{HETZGyRvnPNmR zavkJJ8~&}|WxoZtZXe7$=|j=I;vF{rc~S{dvDdelJKGAsRR)JVWIUvL7|`U+xoqg4 z073>FH}Z&~JA?<;#2DMD*8I|k&J6$le`8oJbFZ4K_NGn%pvnP?*Pf^-_wOc?GWai^ zpWiAOir|O{dZ!10LOZiJ9}{W1G}~;6v1ENAWlMgO9E|LvHM;BGs_-sapMpa>^S=`G zw3k%Hj(abrByhig_0*7S`lGLX>gWil6=h;PK+%pzbdaflo;g%>ykPE}Pt(}XUax~5 zySWj^b*NWR)#Fcv;5*Q*z5hkO(L%psnn!qqJ!PGcs=A%n2dtMIE8%c~B~WSt$LBN; zZa&QR{PAD3LiT;(pM|NO6y?Bv?i~UH_Ns5N;0IHd5Q&6p`h_SMDd)dCCYS+fyQYBz z;|EO*4Dm!{4$ChwGKhvl#sR8`sSd5uXQHncuNebx0n4s+-3OV6TZX z&_ElZFU~X+@b`E-Jx!pV4gTjRBsWF*G%uguDDNZj0R` ze<`+?E*7JO~1b;8?|4Av9Cp%{+wO_x1yPUF@C~k zzU8LHz}HKyvRTBxd1R=!y^B=4XTKA_@_hJM3aszUBCXg>j2qT@Yi)$R;G#6X%9L>k!JC|r)ZkZkd!ctxc}v& z$z8twLIQ%h*>tHkn@Prs?F;F-BTXveYo|6cDAmbKvJC;^{#}U+|8+CN@Iudr(970H zD&J)xC9!A1DBZL|nd3_Qpg0a%top(eS(McRuEpNuEjl8JSTB4~FZwENNW5XOyjfkI z5=8c}MobWDhhL}52t09cCcx$^OQ>e~esJ#xD9LDFsw*iwFf4Zi{CeP^1Ki61S=F)f zgWNI8tbWSS*XdUwmSW$~e|8V$2I7Z;!BzARU^CTQd>~fLCPX3PZuvvugyrQG@VIwJ zi>klMk_|G=uZo-rWeA+{VY@*Oa@KE7S zbruJnT)hVJIK-s1?sncAnsKi5XQ#I=UZ{!r#-cj>=d?&a*VxR^7p1=`v?rhVgamLyaU|m;LoD1^-8}P;B`<@0cPvOp$TXec2uYm zo;c9iW$V3}&y4zd_v30^aqsq4U9qWN`2@(uE7I3M+-R~^Eq#pKzx(mVEfWEu=^CGf zwGlx_@3Xacac8U?=$eye1UydSzpor2e1ZIaJC_8rd$;jxsi;D8&3NIM2}Hh+H*8HbD+G7IiK5C*KMad| z=hNg&IR}z(PDCz&e~&x?`I6$5j>3XHHtoXk#N-Yero%O8I-!=CSHq zSUG`~Qv&q2@(bBBG>3D~|E?+AQRfZZ7#FC?hFAX~Yl1x$fDt;FmRA`U`8EO(OU7-# zP!*Vlj|?tYxHuV4<>SZUrmbywoWUrF;&eZbB8v@)gAxN*XH)KSt*8=C|nTSW}I z0SOSyS*!v#H%wd$+D*8jPMqKAy!FMKrNiq&r*!qiD5L-SWXXBsN&4MTjID=*gM+;% zNW(s}x<}1m4PeUDJ~01XHz+Z0bYJS|OFa(=U>HbENoS$Ib}<+(F99sEou!(O_e;uk zJ{$6Vx>>z-3jR~9&ny-TlsBM*2gXvH^;_P|`Nl;L9%%LsT$*%v^oK5nH;J%`-bDaw zQ}K3)N@-BI$Sx%4nhSq;8G+$aiX-&}pPy~H5tNjg8vH^kCfxoi^rvn6t6%3?M9EA3 zI!zbk&B$80-C`;-SPJRukMs<3&qf;l2tH4^!j5l<6EwxuG^djeewfi>AkBJ3kfc1R zi97;>-bXUfuh~L4z1O5_Fa9Ls%QV-!t1sf+Z?Rn^nzgJ@e{xY@{$L#(k%;VhI2EHAB3J)OG-?&5Q!Mc?W6dN#A=6 zEyBX4%v{)F?^o1TIq1qAN6g=AAs+H4g6)*rx7^#S`MDyeF{}cVfbp3)y8EUa3e*SJ zVW=hJSuu2WDy2gXjGCa7@?Tr|fdBHWLeppgsC=P3Vhlf_uyT>Pg`pv~q(kR(8-35p zZunN+divq?O_>}2rqL()xwW;9xn+97puV}t4!^b|=jz`XA81pbwuPE42`a-iO#8L2qwX-GMa=# zS?U06-T5@7oPd-4sW`d2LOut9gnf*s=8UgC%s%nK9fTxIf!@?0l#EMHqEwyhYEveS zI#Fpd;#pc0Za$pVd?~@19~i?Ek~LR9UJ&|-0&fNTATS0q1n?p3Fve2Okr|B0}gHfi$yb&d3<>(K~-%m6k{oG_D$8oP!Nmp zH&ITZ$3SCC^Wol|YJ9Jlx!YRL&i?jB3GCZR-su7H5xA4)0E$7@j1xhjkPP%&$dlkL zVIgy&^I4=_<{KjY4^PP-o)_I&oY=dQ@!}v^;UXO;zH~y2-|E5so1C#!(8=vpZ@e;1IrTfD1)w z+3a9ma733o1r)O|mjxB&YZArHQ60!pls_5KmG##YX{;4(s2>X1e9Hsg}?lciM`@C=cjk+5{_B}lH z*BYhS&M;!~ZG5SWKsD8ary1(D3&!=%tBw&qH0xikzQ50g)F-E;!u-+<-8sb;3eEb1 z;p1)q8W`+?0u->}AWURreub6ftxE$CpXax)yBYc6L^mT)7R5i0Ri4nufR~{l=?_@a?7l~V-PKi|YqdJcwECs7nw|KM3pE%5G8BtU8lPYXK8!O0N%Al-SgGxWi{89- z8hROlx<7jk+y+-}_t|=QdwYX-aC)%CI{Vf7_cECM0urrA<8JzvC-cg*!oDsV*XMdb z^V*yT7`Fn1akFma8hhK^92=D8w?ER-)TGIyTckhGc=Q4KzU*G>+gQ?!o;rFVoXN_> z#6-`WmYUw^wYwbcG)8oKS_;=jFl-Vj5#k}QvRlIn&E2j)*7LhA$QXSW&eVqI#;E2% zsa?wjU7y*JzUlXpiS+}MScA&9^!5FdlJm(DK>EuR@9fTWoG^x(rBWB90oD5OXI`07 zPDIjpp|rB+she#8^uBSZ52*3-aK^W3!i{k_fhg;Vk7eXW)h44Rh8SB0-b}FL5tj0Ae zNNP9)mG#~b1@M2rS?6v5@&f_(Rr`k&IpOabe$$_F16MUH;1DcvX_i>Yudn?!Y4tIU zi~b&xK{$L)8G0+bd5xI>bGj9fZ%ZmVQGZu*_;e`ojeCiV1}_*A(XqY#O55zf(x1O# zyHsB_;S3`2E`oyIWM}IFVXO3uXMnG+ClDPKB^^_a!v?KJMxH$009Y6R%BGspxS8|Q z+V%I{OY;4KOYW8WOw8B7mE7FS3Yq)Phq@P41srak&YW*{MMi?DWW8|-`p+HK$!0X# z#tYbqrlXIDXoB-Gv|aQr`?{!M!hVy-r~6107B&v zzZ2mf){KfBF}bdMdZReS=J_vMxj`Eh_FE&>Rh9$ITsRT|JNz*h7!%EOSST+=q({zk zmD+?uzr(pd`&6@?cZvtJ@UY--27p0))DgMmq?_B^H}k@a;$5ntY!J$jszx3`o~6TT z^{hXUmbT)3Q#TzKjM-|}%=Nl0|FQc1 z#xwU0uN7L_yPX}7rKjgRkHGWE%1D!Hf6Pr0i~i-^ScQwD)#3c+f6=a>+UqI!baS({ zwKWo0{m0xQuQI@Rhrv-8wRU}C$nyK@i2OZnyD<9~4FdT&C!KDsHQt?W6|cX1u8_A) zMh$nlHpVTV8BD1%C_9>cY2d%V?J$#`qHl{I;X#u8?W;h`No65>o$-*suU5L|BNeC9 zeEI#)G>yWFzri3LHuvZAFk^IQGR_T<$F%*gIT7{Z2X$*&reA4?C$%-57v8ij4<{RE z41S-ihCms2VdU#e%>1g|OCUIZ|P*}IO zw-o|cZUF^Ct!7@)uq_Bzwt?=mGfot?uPc`-PVri;*1uhMN}Kr5thN{eC>Z($$#;Ib zF$WoRL`YxFaECG4bT~jqM!{d19!4ss!nApUov37`1K0Mv%&d+gc)H!OgR ztzkoLYvM@wk?ZY)qm@{N-PKO{uzH42NLS^e;OX5A`o1zKGCs+!+8#0Bi;=+h--*wB zSLIN;L@;P>LqBRLr0YaT*wq=Gv|VrzvpCyUwu_^ATbVyU#c!uEF|*4Ljo+3|2^+$D ze9=t{t@d8BGD}zIFI;gO1GtOki^SyJ74bA8$wO^nC^=lKk;iPzrOJ4hl=Rlmj-Eqs zelGsBkxJbVq$N5%>DJHy@zt$F3P->yBK!RLFSm`IrMxW)atb<y!H0gZpbT#v-1S1%ogC1aIAbqOd@43mBzR8CvkD4Vt4{ynz zWumvb=`Q?7nhK)a?jjp~_s+%W@81F=X)j#q zR#twT@M?yZaEDx$NJP>0_2EYS@#X@e%X_Sg9M zc<9YpIUtuhoy7%qy2Z$EV=0;r8xNUf;1GD|QC~?Fjw9`*%JJ|9V@C1jPk|W`7@EF0 zY@Xe10C+@~O%rI;K-&zAW63qc&WOr1F>kk;S3btFo>p3{#M}|UytA(~e!KqLGl0JF zb5l`{*_${OC4dj`Q>9yV3ikcjENPD!Kfl0`8B;KsWqU;Z_T+ zWUE@syTo3wXV+2gFHtJ(E@Br|LJ*bL9TCf-Q(99!4H$Bg?lBQz{P^do`MR4@4ObmK_al7W6M&f<3d@*#nI!vc2PQ2g1v#Zl&2S#)lLJ~pty%nNz+a@C|q9aKemf{RPab7Q^E5{)Y=(j zGTSXQSlzjfT)a@?(o*MHYxQnD4rNs{LAY}o!V z7%$`S)8u^IRSe3EvbiAQuMjeRTR~WnOEk9hC9~ zMT_P=B#Q<+v`*bkyIlaXhmirrjug+t*MuI}=iN?QDsME&Y!1<@giyFYYB>Rwj$d3T zb7J9t5SJS>q$tW;w&D(j!kGuIb4%`275#_vFmJsMuw+j&lbw< z`j7gS&4?&ycYOMN*b}GZr4B};*MWN4=dgZuqi)kR@I)NQ>p*u2W|zQ}FL1YS!`eDQ zT?Jny!1OZMyWGPAxBQKDIc;V4Sd(WrnAKk){-4;7orWf4uKxNgE*zJ2qyWWHTGnR$ zgs~JsWx=)SL#BL|QaMN4%C&aZ=niQUXC zQqB$-B<*2VJ@YAee*PWTc81@k%we}+vU62QiB^m|vz`63ZGe|t0w-<@9iU^}1c6+D zzV86)>8P)Qu8m98Dd6JK5hfiCBrw*$wH`!g@@`PeSsX7$mF;ZD3?t+rhNT6>2-Encu3ZxmCjj6oN?C{>`pmN}y2 zbtN=;!@FG2C4&FvpP>4@?9J;TwayS$hJ4{u)5xjKZ(z5x;rK7)+Vh&GjYdl z>m}%IG|ojNk&_ceF=+pV8;hy2MtV{V#-$)l9g(5aSS z3i+B3yROt+XLbCNmIn3=67o;3V-m&}1TdrJmk1xs0akcsp*&1f>g`ug30>VmXeJg% z)1N6Y2$Z4vnI*2`c#&0H|9d7+Ylag=(5JB%rQQp^GxPT;zc>3N1$24TzM2{UUxWX} zDL9epH|tBxOJ?i5oIpbh$QiL0Ln60#7iXyfZ&Y5yn&|FbRoDCX(-qL>`b6(KUV@CT zrJbeQ_1**z%q&p!2vK?Yix|Hx0!&MbV#heBOB;S4{QGxP#N7F3s?l~WGq=I-ZKv7u zO#_jJi+SAHX{za9gC^Gh-Xmij*4){ty)})Z@awdeV!~-F6vIdO|tEn@%L2^@Ae@{wb|FhPfo2`oz`VMg^SD!>)nm&+ne9b9{wS+BBNjEb(^kDHbR{}v$Z{$nmx%wJ_d-T zl~vFU?@k~k*$V9Zd)APn6SJ^K^ZHvb-coMvrD6ubJ_2)X`WM#Y1K77zr38XVrL$D@ zsq5_lLE6`4Icd&m8EFlk{~j0V?8_yJ&paUMgD^g6H=oYz5A~9AuamMl7K!p!c+W5s zzU*_O!;j*8Lyh562pk-@Hp48I>pyt9gC;X^S1gEZxe71sdkaT3{R$a@$BFeoL2=M4 z`1oFpyh72%)NN@2oXNThB?4bbfHwC(ZqTwb~rag1@#hi6g*NV8fT(*dGB*{|8~PmuDTQ^)7=9N$?y}-hy5P$+k*AM z??WhfU502slS}M3jS`jUOFp=NKe-3{V!f#PU~5+7{EV0s%#w!?^EFSO1d=;7fO6`n>c{YaLbKnNIeQzRQv=yH_`bH9 z4rdAyMOHjy#(=#uUO+&=@!7Axe?fu`!1WFRSLAg`bKub+yNnxPqc88gPUr@Ggh`?Z zF4h%Y-&`V++I78mfCf~`O{LcUa_c_5Zl+_pDKO@|E`U#l%SlxeMH}C7r~5 z2hQsv_J<1sQ^}OG`<2%KrbZ47MfIC=AXvrQB$-8{-?$KA#jBWv4r3LVC;pR5atae= zv1bBbII(q5c{=Qf&9vWa>`@^Z^s4>wS3~FH3nn^qpbk6)T`0%|sw+NiI&8-6uJk7q zj9fIycNj{6t6o0vxH|#3;Lbju4N#Ev`GC$+NbT$Hg$K0%z6dzYv&+ME&IU}or3LsM zES4GdkH>6GvGnIojnXMDIk2ChHcF(~MUlw&kv@_k}R!rWR2O}1Xj1q4yj%S6$K{Lm05J2iapX1V+^TK#de%n=TF zp^f^i^dO-(&y;86<> zV+AjqpGXGoo_u1@i;Qo_e+CCzThEp>T+N&OkB8cCh7*OGcD@;NXR))l%qr2|4#;%d zlzot@e1lM_0?;eSm5!7|J2+3AM`s?2O;%1{qh2wv8DXRze7ISRX!g$XlCm?oyHO{} z-2$ro#l;-kF{Bb`!$=*L&p}=I4@Y#3KcNTk&BTgLg{xf$ zX3VUonh(>rD%SSF{zzku0XClIU{LfTqgSd^+Ad8TvOsjj5(&y9?E_7TC$sE6H`V+ehwJ9c;H9U~!&% zUsLmw42>wRvp}pQ_YKa5Co@Z0%^c_W*i6Va6qSLCnVa*-$ufRV4c+KJ7|#j_dr^1e z9+!i~USYy{7bAP7p5wO9`9qPL5`pzchgr?uLcwRpF%Ze-ORB%P}TFDv6^!C_9eqB~dzFlYC2YVr}}dT zBrIqa8-fTtVIl}3KZ3B?xnApPr`#o@_RXVwlkuW*Qk$rHWdpl>^)c080f^;-dz=ee zU$VGql^$FM71NBmaA1lpC*j|jFWD6&Pm_o++5S*BB}nOEVPrh{*CWzAt z(kc}1accCV{2}xYSM&AFHjLOr6kfUm%ksp8@ac$w(GF7Q<)z-JHRVnoo?gqo;sJN9 z_*>@&Lp~sSoj;Ab(dl)2EFsl(%&R(@%%b*ebozPoM*vF$&kjJT0|HZ@xj(gZ7Sz)# zN_JM0XdZk~9*PjCW3mf}+8q;Z46+2K{L}j<>m_)%(p60(u* z2t~RYXBGStZ9#TR1>C+aSUSl`YKuBEVgGo@1U4$9J6CBR=Zt*qDZAC!X2Ou4DaXXbvJ2VzH7FitHZ!nTp5XpHE`-C%O@OfN z`Bz{o_W3h^A7eYc-&WA}I}l#_R5J7EjX-1|U$X35q*i&uqc#LJqygJ$VSR$za{B zJ(R(f_1^*I*h&L2CqY4KSCvB!fH>7s(0#dXb9-B@R>wRg{kGr!WNo5_H;X*bx%Djh zF3U-$-6}*Pi}4FbNPX+cVbBi)&7QueVzt3u*X8vK4ZjAAum_EFwj;QbuD%7GrJPkS z3-7c_*}vAmT81)mKrd{pv2zm*)?NnBQKVRc9{tAZ+w=dS<{$Jzpt||+b_oVe5EvN` zbwyavAY~hlxSHa>{y8B`4+g2%5wXd{zS>*XjNA=iUkp_D@-nM#E@?L8dpfloj07t0 z@Mi;>U35x6R6CNk?`(=Rer^f3yyDz*WROUZ=gE4NY99m>1nkWHoe&Kf&l=^pPEX9& z&Gz6`>_E!c$lZBwXCsWgBed=-y)v5G+T?p2?z_-&1sZQgE6|6LZI}$v#%?_Ts_4^^ z3P^0v^8Vn4LRY1jchaK8hXq{~68!H-OAdAd$Wxab!ys2zjl@V;FMOAI-Jcc}g2aqJ zdV`OFw%h*M$?uLYppJ0}rz`*cG#Vw7`N*`5vX?qFx8F`Z?N?D|9VE2wo&OcI6tu%h zBo%QW#^wlv{9g_V6>@k(ajScU+E#G=$If2;sdvL|h?-;sV0ok1hV-vrzkdGwIc7LT zcivlb)od)m4QZwr=o)+bz_1z*#4*Y>&X!?r9BhB10FEq=i|EQ?;=~A`yPfWk4&7i` z^o9UFN{NL#m2A@M^t}u|^wTL!0DhG^;;e+q`3)aN;y-be;oTa_o7E&$`yo2@7yDZBPnUVsM|UneayS%I5G zy9$%>1>#C3(+Pvr$V<+jg!o)sw~n{tad!Jfew@z-wF+P^F|7H67L^)}t7}9k>`5rZ zPVY3PMAan1wDf7|TqJ4Ykh68m^2+t6AHx>t5G>iB*NXyO2}WMv&JR;{-TK`EV9_$2 zeI;f+rc*AyU;cG7SOZSZBzNHt*q0xUs@l&5z7hGFPn8eIPwg7Q=e-B-kU$=wsmTm3 z*&ztIqm#F{&Hn;_&N=U=P`ryAue=mXx!YsE zc5M6tqEOtPh3nx;8faq$H>F@V(1I0Ac2Qk&bWK~;#zpwy<+itt4E{J;-Tu`M5(w*9 zhJ+-jVn-gU#A#o}(2DH~X-o{d^g%HOF1tSpO);U;eu_+bB{D^v2$^?x`a@}*;5 zV#q4EwSpi{29SujunBN=+Atg`j16DZk|SHPbNuMCXi`Xe^d ztBAb#W>IEL)y1^pYgalYwE^#!4s#&s!!2KKU|8>8D_?8k-|=RaYP5m%EpMq%s7Rkw zkcEwh{qf5#&f0)<>*+j-@vPYu$KMw;YG94}f<#zF2;-`K5<`r8WNCbY#4Hlm-_{s^ z8CQ|{5;w-qM~R}y5`_Wz1EKIIUrctU8X=ApdEIk;2YWn_BM0eA&_S49H7o-Lk=U{L zmLp=3(A3LwPo?ChB|-grV~bETJ`X5s4hKBC9Sg6;hJK_CTyt&C^>>JjIf6roP(A#-m_1>$=Wfh|h&fY_^Rb=go(( zYDNVj+00Np?USDI;sVIKTf{!*zTbN;C}fHVv`*{DcZzW+wzd`m`>j}IHV~0R*;UMi zZ>M>+KFdmlmTE_b-LQ=#>lM^Z@#<6@_V_;ip)JQlL-N6*bNKE({_hq4#_k?BWg^c?p3<)HNVu>TSkf4?KW8WAjVB3ITey=z>xLvS zaN~t!C=LOwYF5jmO-_aAJWAra);}u{+2!zwWO*(qsJAuL; zz)GX*UozHeMjWkv;BOWh=}0Mh%AWU3W@)oSH!5bWS`;U#A+u1(Uafy4(O>EbSYHS= z9HmA)gex)8rpA)|*I&XQQyBYa+NdB)NZi$wxo%zf$E%36NFlwrE67Pj;*HmC z;acgq8+ex4WNg3WhHRfQVD1H)w%>}LN>zWskB>cHz(1I7bquJvuO^5EP+?t4)lI>> z)pzvC*Bx)@140`dx)yje|L(jJ8%<+0+yQ$4V^iXn7a*F$ST%336QEL%P(<$eJz03O z-}?vbP>3Xv3JfX5p$1sXORyoh)NmmF^wF~1vTC0un+F5X zV*-YnlHO|8uOl!e3V+`4hU>1BY|(k#kl{a zx<<}k<>eX628MkzQ)gof&o1n@UMs^9c1tCch{Ml|cEo^)yT%kA5^*vj_MQxwv)Ozc-JZLxm{Oh<9z1`D)k#5ZEd z?w7-p0=D^4z85h+wueHzI{mxF|qwhX-|wLn)5slWLHAi@MY?vp~KW+1xadw$b z#M|r{65~{R;rWK!x*?8wv|FWGLv*4oLA8+Z3Ikw{3NWyJKWE$cGX(Q1x^cVTMy%5K z{y!^Xq18sCV~RRW#qiQUi25kayUAvvF!ZftoK7AT zAtihV0SVs#&-rpX=q{QIvms?eN?kGC5V!7q5_Q`2jfFKNN3x7L(-N!nv_x8d4sYRI z+|rrSTi4w6?;l-{5l|Y8Xj$|by{i^SjuC7$+rW;61P0t&kg6*=yB0qJHI3p~R;BM< zQx=DR>4=#P9$9hS_?(6tl{b6yNb*}KDcvTJVXw;;*%GL+3l9pv+jiUkI%9agF$a9{ zoEk$aJKyNqEh-kAb8V??WV)+S@I&tf@hwf+ST?I^w7Uny zjuG!?Kpp4JX9=J4w7h2ff`C4|_}LUK#3S z0+%ArHFB^#S&=5sE6Wo%t(w~ll>WsstR@-zmmh6BeQJzBnU+DiyRI_;U>a2=kR&4` zvsZ#P1X9|tvP|RS_56I;&dD>U2N!;Ks(FHeXrb`eV+12L?l77fk|togOUleJl{v#V zcn4IBqm$!L5U54>8wU57;HazriSS|6JmAY@tf}K=g~#+O*AQF77du|7v|n&6p24Xp z=)_V`Y&(PAlY*NiN63^np|A_9OnV)ycP=z)UJ7;KCqp`%55h~5q0(214qGj3jWG*J zt9Y_X;v|;c>Amri)p9X((6^Xpx73y!qiz&!2RUxNXqYc`;KEC#ILwrF(y@QELXi(* z31DiZg2T=*{^^Sst$UB4&m^EOP@_=CFJ(u8BN$+31kpG=l-jt@Gv-oyt}PcswG`PZ1id@n%{cjbyKyeg7w1sEQ$Jbd$7@#nSh14yQ6DX1T%f(!3z{ z%G%^e#bGaI%|VjZ@{>0D*KqIJ%4w5(QYZIzdGVmHz=PZpGrgA{#kstt{l|O5S|%bc zfxO1mHW#cn(@=k|2<+m1=;n`j+zgA$?EMrR&6VbWhE)oT^-&-7CshTjJ8u`ovn>VcJ%;A+o>AK3+gqp*pBj1AY@Cpt zb8&IRkU3RY*k0T$-_*Daa367$iQzoQIX>upB^lY|*=}NXqEF;!8UltAnpRm?-U+rD zkx{?vF}{`CuKKK>C7;D!DDq!gv__@~)f}uhLpoWO=>VG;&WHx6CjfSu3f$QxDZD3c2 z9y>J32oq$4$6ZIVIa9{rgI7(FRS3gxl?^HQhqfw*^R*F>wgs*Fn`fFwuq9wf$gm@X z^bka)D5J!1Q1Tic@rmo(9!@Y)e!OA*?cNt_!LK0bNDpeJC6AlCI;Q_PY}TaYT0S-w z4}_%hYg6&qoa!>beyVo5F?U9mCnbr6NLM$X1YWvtOT5+!V|b?c-;K7nN(92P--zz8 zzS)*~6yv)JgXqCFFbXier;xxlXnKeD7&VE6cAcp~{QwG_RM!63Kobh`us=qwB!R5^O{X6bs z{)5vwzT-wE!G{B`w+oKvE1@8Ikw!`1@4vrkF~E_1@}*zcAvh+10#OEchRL~|B?DU& z>B3U{OSyZ*xd`F7j`nKW;*f3|GYoBYTDySD`O-jx%R!DlntaCI@QMMB`` zQ5KqR<9_e;s`qMYXDLG_$UP=r0JFULfI&`67{y8wV{~AaEAng_L5zGH@gb7uKaF5z zWNi31a6#3XmAV(z;UUp4Vb+CrMxVb783EZ7<6a+sU^S(Mty$?q@wh`rondYUwdtl% zkCJ|Z3;f$(HW?fkGU&1P9|N8Nd5ochv*|8XHmBaW0-Mz9kaL(Uhp`uRCb#7-pz~k<4 z-V4&OXdKy?g?HxEchg!%pJ_>vct#PFt{sn5_O?enc>l8Ixu$e>#sXAleIykGm^6sS zm){kFzy<<=7$(;A!zD6%+2=PDLqwdbFw)tI_?jda46kkIu`5ej$&8{6NEzi@im%l= z^Lss^sIU43x!tQU_o#*KApL?+UIVcpX;(BHr-i0-`)ii+l))rs6 zk0q;^gRNJE2(o$z6^Xw#jf)EjCZd32Q(c>g2|t&QRww?NISlwbKh`gRYmRzl;BnF< za<61$weJHzVP%4)UA_0{-`)?$q`d`(u0$VxnhEd!`SEcy*O8WL6t|h22I*dip9N_-LVrLon zaIjA<4;&LlxwXHtf-wPqJ=S+zJ;zQc`ZmUyJG{ z93<>$GxC2WiZPkcC@uB{NfGkcJ7TEl_eO&Po2(kcQVLo+ayE2Q@bgm|3N2PsU`S68O z0vqzVlobtWPVN0@zf|*ciTETBfyW|IvIOcd7-Tydoba7sQ2aQSG;e(H#h>i(-n$*+ zV8mpAzHysVxQjK!5jRNI)BCVX{w(I-*)r1UV+1~nA2}^L9T4>vI7g%M%72f$fF&MLaEM z%?r+qINm~u!ZY+Y#T!;jLi4BQM{21}Nm$AT^Yg={WJ$mmW ztC6aUHWeAqyna|o9skU=o4=ejtEkmJqxmFC?{@xaU^#4C&q6}2YnZn6v1E z_DgZBc$8iv95r|I*3phXS6Vqw4%d0eag^*R9(0t9oGA8#ix5}R5k=%E< zVaU{aV@65elVm=y7zCd(cqS}f|6(A^5Wb^U$;O-_7m$I;_2Bq?-@1LGgqJl>_41xS zWKjQlO(n+^TL9u)#)Uc7R^|wBA?UGjE@&_ap#A7vYs8^;9xi#yG59l;#c^X~^dO9$ zWPxbP31Kr;GAQD~b?a1gwZ-UT&*|Nr#|c0OzXZEKh`EP6ZsB8Z1e*XIaOV3~i-lEUJF8SvvZiE!lD4#FI0t-M(2HF4iPGu&_ zUW8Qn-%KR}I`HgXnq$#j;xvSYnEi`;qjWYjT3t^9i6ms&h}*u$6@8v38opi05AH{p z*h(rE<<*&cBILS-Ahxu?M9yEgd6^j@>Jz-`TL14Je~AUQLj}gAUgrHVF=nzqY7;N^ z$f(s{u&bR^W;;Q85WqdgOIY)}oHCB>3{?W7kZaTx-9T$S!<}CC6g=6XhM?agrgA&^ zVWK^}I)xrIHU|)6xN5b)YLKmhcKwYPMQdyl*~hvMmY?xRnwE_`5NTgPrrpXmovr-y zwARs`!1+KR2lNAM{SI36AqF>yDx0v3q0zpj?yOD%-aqmAD|00m#EHB>e>TI7MgKb6 zvLIWnfw$1Hhyeb0Hb)9Be2mAXvDE2UQu_EG8Qm5;{SQMN)pFDr8XgUM{)R`bQ3Y~_ zHWvD>>ifj(JKJJEv%JIv5?k*OTl}WV=I=BN`|;TV3ku_{$r1b_3y}lrglM`kF?)BbAkP2gXBKnBB`rVX zn)UwIug@{D*MwlL>V8r|<2fPmvT_YG(5mmoIeFC#t*2@Azh$-i+q0 z3x#Xb!+}SN5WgU|y`+gyn-%qwb!60){otMoaoM}Gr<+0`*@D*FQVL|I8beDfFL+2=OM?EF8rA26 zwU0P8nXOmgSD$-BH*tP1YypMi!k=p2aeR6iaP`A;`(;R-y))XRV)baE3 z_ao1qo*)}j07Ohj#$QIJAJPx6z@pQ@GRXM$_4d`a zP5W37*+ulqxh^@|2x9Oj$bZ_KbkhbJ#?faSZ2!;1^=4EH9QCfpO}e zAIw>cPSC>2X0m%|nkZ9ao70uhv^rFu23KfYz=V2uVMG*S>!*mJ81Q z%BcbPC^VP-N8 zip(7RKSy6 zN~>*N)k)(^QFtMN#RA5`y*y3?hppdDFx3IRUU# z|0=2CJy+i66Nvs$qO&^YwX=ORJKcYtWKj5Z19atB^?I;+;8fU&`f7AG=Zo0Hdxgpa z^kJ6twk2*s7s~;h`PKqwd3kHQuGXm5=WUvX<)g)CUi&S!RJUL^*@sZg9 zf2InZO~&d-S}i0;leEEI1W=4a%;4^q<@k=vcXQKqy!O^X<*}T77rq@HGs;v3`-!@B zg8KrIvw<`#fIbd-{#2|JYdJ3Qg1M_sJyA73Iy$;Ig3z9a=KB@byXJA$X|G*@2bXXJ z_M+=CV6VrfxutpMx)%CbU=F;pQNlcp618BS;qb-da1sg24$2OpJ-H$MU6A~{U~eb_ z4$tkzchs12)SKh-&dK+j};JVVPNo`dZGWt3RtGsML4S@M(;g*vfU zgmgzo_5F%2sY~1r8WlKXZ`!0I^XyIAEAkd;wn**>V~&mfnwS;?X6v1*q;FEJ@ZRgR zPKib4UD8?C@5Mz#ezf53mZ)>EC*hLV>j*sHhfLiBdQH#bxAFB%DK+S#{a&8XO`hvy z%F|ZJfDd{%i8>4M_X#cDe`g1(iTj`y^kJ#8CPM$ti+)Mh5S=(HS03Eboi7qa7#*_% zmU`vS$(I9Ogyb)5C$SJc?zh;4KxH5@f!WX^1x`7po*)(5&9U;cR<0uXdHzCVDvEW; zJmz!Leh=T(%1`&th?(CLcaYm|UJ3!BAd2RFPn7JCK2bY!^~bs9bUXmvyBiu2q4tN8 zO7Auu(EZolD~tP?j4Hz(c2g*nNzAF}^h{k@xQnr7?;lY?SXKo*J5t%@JdgXHKO z4vIl(tb3ap?C4-3KsmdZW7h#9s>c0qSS*u43yUfMfc$VFjf6V@!1LjS+@cP5GPn-y zw>?#>a~8pU{7L+Dmz#>llkF3sLd7Fxw{xCEK&|8=JkqFX#RaqMf=+FjANS&)9R92Nel2~*4isM+QsMd0KlkE0MQmRG za1?DyDJ`u~4VxvD;j{P7n_SQ4doX*x*88A#O8VSI!C3k!SF`CGAwQUxPMqm-e;r|7 zt=idX=dLfeXClGd;GZ@Z~24d-@4|;`b>5v-! zG>{_wLMlC19w9^=BB#3gAd)Au$b;)aD!4CuJ~f_}Q0f1dZ(D2+2**BFb*&p$5uvfD@-)71KLNx0Y7qmTCu@q|lI}y*+5`XQ<_~E=FBER#O?G%)Ti~ zbM92Zre3f<_!-^b*Otl(zq$q@H)I1|!3hpYFfW;bc(&x2ATFhr7g-rqF>wez@^~Ds z6~Kp;lmVZO!&LAQ@CaG%;HTu&r0jgc?kud~c-F5lXIed7>}F;R`m=K}o`&qwI9b6&(Kr%k&*jUt zKX(xs!{zp?HPH%2!o$f6@Z#hJO(~goFwLh25-`lwy>OaYi|U;U ze-OK?3=4(Pcc#VHksx74%-^+u(jqoJJ={SqMLU2t_98Mpzk%~7_%)XOXVmhMoJcB0 z<-356Yt-~(-tD2|uWA+v^w8cSaG3m2OK_D&7z)Vn9&H%3oPFJ_sJ^>B+r$K1=Qp~t zW=!wgiz3iO;SNDL1>@B>^*S|ZMjfj07Z-b7JehMf4#Oa)DRu9NH?-lPPm)Kl$d)U2 zACzm=Qc1%57strx>Zv2x^=XlV+gS<|cK)wYQOr+_Wrl`110J2%pMTQ)d}+rRY=a(d ze|?qyY(Ern-by@Sr!6}#d(+%7?ywBd!~G;5==};ftdtuto3w@OR_2fpX3t*>(4Sj= zEY3m7dF|!CTn!OK7-BS)j(bj4ju$;xxp@b+T~3@5>CtM0)}O_G!Pyf%Ilsbwv|)D$RTJ8F;$o z<>j#q#uuA1m@_|X?l+qLi!^%)Sr^MZg=jAI*JJpgUrm=Cm!Sxp!t1SX5mbTRD z0Mv&qbQmBmgkGf%xCXH&tJ%sT+UsWrz>iLz5X7{Bh9{eio}Uv!&i8ixIG_mn8g6F+ z!8xLy%)|GA@87Ze6A>ECi8F?ZZVWb@hU|Mjh(UhS6Sq@(Vy)oyMR?62%NA#z&@pwn z;wT@6si`oEE}o^T!aZjeL#4(Y{B%K|Yx_QsT8l3}GPryki7Z0*7IXf@h~uqOozz|c`3_mGpXv1I$S>~dhl4_vh>u9%qK6#hsJ@wE1z{^f}Y15|${Xp1yRSiv^aAOQ# zH{ULChm~+iV_F18)=#O7Ws){U$ywlE_Z|})sjC&Wcs_3Em#Kwtyp^ypN+aa+6Vds&Wg>IBHA~HUF&ScJ#>Z<1JE}sdH~jUwkB%uv*+wwM=$u zXOXcaQwNx0!d?i2e_M@aF&$X^B|=K;vrj5e1D~)$)!v5)wbLGPwCQOi*_>VH=REKomF5|6t5-yjf z{;nY|ec^Q-AW4`V#|Rm0hjpK|yi1|Nfv4{``Hib`%7MDw2q1Y}!zG)AK*k=LK6FHG zY_=^IftD6c^#H@P>;NAX#-6NDAffFf@AAhDbEoJQaN$>`ygi8D2%ha(FE&%-pksB| z^-g>?#p~DE(dNeh3W(=>V4&jFTU?z+as7=OyNNEy-FKy)Bk+h!wPAdsZpjaks=4;h zcLmkH(@(b8tT6o12RWSqZE~KH$Fr6&&>qe6&Sat&f+Fr$jx$ce#=@rxduU8&ef_2y{G~sX}Ar#wDsxLwf`;Oz=^q87@O@H zPG|V|Nttvci4<6C^QkVWlU9=k3lVk@0R>Ms=9Dn0$aFDh)yBi0nt?;iJpWiGDt=rW z5T?%9 z54N-ZU(>|g0LZ>BvRJr2e!AknI2#m)6{D?&=1nt{u-3$DJ(S!tx=CX`0RgQHfS*8}rX?@kTIjMTg4O-#kz z(FvxT$g*HmE>pEI9SsgMR2Q7As&6?}sn+Ukn6&a$j%Ievz<|Kw9(ivjTGe zOt{d)0~Jb}_*c|f9IP25p3+>HV4kv5(c3bnKEE4~Q?)t(MBIMiAvAMWFh8?}h%O?J zwdzcBL!PtgDFwC4ns9tdZ1WND{Vk2xN!uhpvh=x{5E|;4+eJndtxi5q^cLNAf^*8d;*WUgeaPR*t#!8pl6(RSE-&f1}Yd zA`1|&*^+hU@1ZcWuDWD1H9h0eZGPcoPT zjp_Ja0J&zkJW-oh%Avl9so$Z?H}Zsn@@T7-*7mrb2?>(Zej29vw{h{%SR164UZxjQ&9udqx8Q5r(NN#Zbrhc{v@%|ma%`A?I9?6Z zs5ORw2ZrAEGn^Ck{fE(fbd11M$q`DXVT;_DNRA~0(2`Ue!5*XwTPm#`&$CUZLg~Zk zQ*dO#O_2Lk7)v8cjSCehwo4Xn%dXHzFri&ZdY{U}sfCeBw4dou!0{hY zqb+0oNw1(6T&7h1-i-h&5+FUX3QcfZChi|LMx>6B>zXDd5wTKMYI-qVr*V6h6p*O< zaD+~8(*sh{UR(#`Bbc0Wo~))J-?BLexs>3He{)=V*NmXoHtHXq#@)28=>g8#@XbFU zImK|>hkDW9H+BhaqfS6!yl2szX>$rM>!sK(K}#%<&#=A(ZrD8h^c&P)`QgC)#9Bo2 zIzST+kideYvSQc_Hu1UyvK?w#)k5fRX4!qUQ6k+Z_j+b8Vvf*$f*GIxFO=LytgQxZ zd^6dM$}nT>z=cEbk*S3if8-WCo8H$r5{I5&O!nP<%Sc$})plRf2Y?_xgtqJTKHG1j z3=}k$s(V+bMuS!5J&4{x<3SCH%VWO$#HbQc;G~sUTJZH!`lEvOvV@FfRGS>8+$DTS zHC+Y)C)CgmVZ7!~XvimmTo5QZ!!ZWD#|>oU_NUNd6gb96|L_}JS~Du%z%Nl_{(G68 zaG|73NUQD&F=}$QD|zu5qZM*1gwHZ&@T>NF7TGsmsH4`pyLmo^1L&wzYf@6f$0K8A zXTs{QSAF7y>w=a7cKpoKPO^r2u@c};#Bq(3BV$V9JHY4$0S-elL*vCPO;5E zB*pW>H6F^Y7DquveEJzw)LX=2DukC5Vo^I+@xRySu^1+oQSw@fNc5~7;g5f;2Ln#0 zkDeaE+OM})^39L$mJ0FGcQq$b$2O2FR(08D5CX7C0f9AcrOj!Pq*0KzfG~uFBI1%k ztE9O1s=Vy4bb5$VYW*&45}ur*I0_vL0A24*B@@xSew`i!_i>gKee{LhMtJ#u#jUV& zgI@4#;v!joOYM!UQzK`hB2r@b*=U+MVGrB81C$^GVDtn3+cc;;>*6au=o3)-pxzmh z!*7Bvm-CY_+GKC+45GqsKRdT4m|9t_E|_L}E?QKFM0S9Tz5aK$m)0!2fL@5@8Z}*1wx?gD;q_WC6>L~ri3r@}Ho>y{i&DG7@qUuW?VYt=tcHq&V4|#H8w98{= z^83CQ`hz*~&x?Caz1AAo! zY1vY@_05HUD74Sdo%VTiXX01HTkZ!@sWVdGwDvTS!fqQ8qy61*Wk1adn%A7xh;mC+2#wIp!IyJLf0cq5d4y5xOiM&%fbl zPw?vJ1E=PuU3Ueqbv)9c88a6S*S?*}P6?Qrnof!r=v{Bv`uwZ;sN7Y3Y_~Ixm2t?*ORmm=TP_Cn&3u%KZKYG!k2S z@4s72Wn#XQYkqOJ*{~yzE{~1ZBIBOu`4E@Sx2&==yx}O)@R$Cdg+l%+5{sx)Py*tE z+mY0cPk)17bn?vO8Q03oS?c~4@KF(Bb^?zZMg2~OlAB?`4rpq5Sii>tNz?|h6SOfE!;cSVkA3>2+j7lJJVlfYA5L5ND{uQT~HSMluQV zQq$BN9RC0B-h?ZP2ia6u-*vlImF!c&6anfbSw|{vc!vge=Evs;vRp2;&d)LZ8e8tZ zG=q2@*~J3D2rQIk6fV*m3oM;<)cw9Gmddof=T*7k*g?qkZ^7WeP1F&V7Y=aE{7A>& zn|!hRzpji-Uwh`qytMMluhR=a#sF9qmc~MioJ+S z2{<78N!P)RT7Hv9`IF(>40QC&r2p%h;oNe%9IPltptEql^0Gm%U(>{a)})-5KZQtvlXL>i7r4b8 z=!1Y(UD(^RgL2EK*pNe0JOYtDxmk5jW#Z?7uQBBNR%-tLaRDR|^YM=bREC!sI&9El zZXf+XH^0rm2a=NPv4`5K{70N&fHO;kG0owgId0S(2PQnHL%Niw(WJNoPeOyIynuA1 zm)`TL>E|4H5&)KpzjHZF&Uyajl1*4vf(%5C3VymlfRdcEQn~Y=U!RBnJ#W6;Xuf6t zOpFG;K^U5JNwsBGvQsX=Vb4Q0VflHCJ~kqa&&waXS6dn2%Tl@4;+#bp zNx?|V3QLt)0^(R_E;j6AJ9fd&t{2oK91#7v#sR8Z611yZnk zOkeiRjjbASU`=w>hD|Yvn-CK@KFV#Pl1c5s>&rB6FH&}VxdzJ?TtvM%=kdvpt?H@Q zRQWB~%MJG{i@Jf7o2AMYz4ru^>YPaPA)B}cp=T~-R z34$gC(njU_5h$bbW#M4_X3+&t+2&y2ty?mP`&l`78r4sNYEu8#oUsc))?@;>Q0BDX zlh_#kx}HY27X>C*Jom@bzds-@x{jsSZ;I-~DwW_;$wQPEFcL5oKYGFPkg*Ain?o__ z-P?5@v(kd2#7o{cjlfHHmKUJHYeVFem35dy)Y~B20b+lDUJk1lW(A(9#pG)|565vT zs6WxOIgJk?RGZM(ZB56X9edSYYWl#!ff`PoRjl|l_3V`@G!egAXj3;ALX=?iB4q!Jm}$385B((tuL~tC;XXUgWL{TEWXu_F^zn zAM?tog&)-4yZI?gpWW)F!xJ&*DUo4$dpHO=vSPEI;9HFFJdHT^e39%Vo1}q|_qeM9 z4ZMw_3!q{+*hj`Z9_^WHz}C(Q|1;n~iDaKKW89{~eF&RVk+P2sy@CuiNA*fyb_W$p z+wVvrig~-$s9axtXBrY<2nqnl1@9X1KPfIj|EE)bGd2Z*^^U;YS!cFDD_D?v4wuI8 zPv`6`<3FSp(rsfTklo^^r!CQ%H`y_B4-!6r0_kUmGnqK*PMYq(G5mIq$g@k2|JPB| z350!SQZsDYx!}=>ojax?tnmIEolBU@SqmT=o)7f=aj~6aC2=B5Ae50AwSFh&!b|Px znKpOQg}U6MrL=o!zh3crk?@Aei=$D4m_|NH)s{@`4YOC47t0e9DVtwoxh}izrF3ZH z#mUW(4~zFa~8w(kEM zI=pWcHPeJ+VFQE55!m*sp7KY5I5bLQE|L5#@p1Zo(5M|p0Yt=-@S|d@6AJN+J7xO9 zH6*&KJZZcyV;Er9sVcaCq`Kj3XVbKKWYJ(ii(O?;WTawW8~xG{e+ml zK8-8OY8DojA68UUwIx^7kHQ#_FD6!>WLRu0!b!NU8H;bOtQ*aBkHtXKGek5D08~l7Y#O09!_eYs&GBxX}x149C zvrB@52#d2T)4@%2^3T^Hv}su)I9EAf=m_2Z?sn6@dFaQ%LgIMU|8fL)F1Dk{0KN1> zLTPU~=&m^FNHKIuNK21>!29f+2}+cfxwT#Jj&e?*@p>Wwyq)6Wga99?nD|U2V$^9E z{d?lkzK+Htc&pE9M)Iq`sF$`zn1Hl8uAK3vf1cwe9=~B((?xX1kOl{2F#kM_`E4^R zWDb7#DnFP_6h9>m3!z;{Y1jiGr^WEMnCWLj9LG(j8JP-?!c zCbft<2mMnUR?-|fJRCI@v3%+Ll;CF_Pw5;t^)|&8ac8_`W3shPeL;dryAMsVC!l8x z@U^f+wT<}__ke)*wg172bSBe}xdtNK@lM&xI8}cDhzJzJ-2KV_(-lhtzwxmSJMK;V z8t1Pg^MX-c7=!Pv`mAT6sC=7s;`((=XSYU*f$C@tr`qyhEH5{Yfu-%?`;>gtUf1Xh z9O*9lz0u_YA1U5^Hd+~N2b|2YW=b*9e%Fxf%6c-mE`U>HRo7gK0@{%UN5Mov%vG} z{0H_TAuu*@Z9<8Q?=B#(7afrehhd?Wkt2fRg_cB=>HRx|YkFb!N)u{34gcUZ7+ z;6uRBkB~?ae`wSGoF_Sp9<$8Dfq4B9ig?@Z$_4PkuSet)*4%d6GpBUm@bLcvxZ$?Y ziz*95wyjgIs2s9QkN3L0rWM)T@}|v)nUAo_TM1`wwmdD}@_b2AEK|t*nk7P$@pp&C zExwt_EJ(x`zTaiB&MpHV0$zmN15J_Tng%iBX+mrbe=FRTrrunbTsqz=_Eoa8ke~sl z^Uy;)R_phhJoSdaSeAY^*Ic$d?^_XFcqJ@tXlrbo>GQp^>OP@*o)uof>Y!KmWnhH* z60Ohj0l{k0C9EADED@^1C0!bQ3c_1M$tiZGE)NrgrAWCUO}yE)_9AC#!Oj8tdJU(n1{K+dnHe4`I(?nO*&_dnPy1C79&S6ZL9 zvjgRXL9M$Jt-N5ZBfWIBR+0Zc$3Zqr=8 zw*MikU`)i)FJ3{)@~70O#*4s3J!h+dh6<*2wEvHbccFFibVDWNX$TB&Qrq6en{LU1 zpO-ZW2@*zQ_;STOW*N`0_voPq6-k_6PR9;%WupH(>y|0p9Te1u<*EVn{_OC86GZ3^ zXIfE^1xT8;5N|`a&ncW5&{-1fPA3coT8s0`YUMcrXn@eus#?4-c%gQ{~6 z*%7h3-kW3uJHK55A84=*+}&p@d+=@$DG00$08I(z^uJ^1pB7QCDY0jBeExc{O@jEx zZ~vC^kyeoKx{lCMN0Qm^#B&j9nk}9mq`hcmJGZPY)A-G_QVF;@iz zqkJB0g8iK$JC{wjt#KOpdtXTX84oW&JVkOeCgt_BhBKud2WjkdNtxgRpi(i2| zUC{qJyMzU~wUJ}o3BB!%k~{&jh^5H-#8Vlg(ob29hXg+ZvGz1fKEDYLbdAo9O=+$T{k4&5TW~uiz1KEbMEf=!_?#t>|910vqq>z* z;G(f#=8ec34GUpRhi%{-lWLHQc0%B+22L1quU45iKT+YC6-95;S9u)A6sdJG@YY&M zAf=G$;N7~|z3=U;c43n?pl{TbSKl)46^=Jm>qrwmf^cAa`s`BJ0*8u3jFb^SJ^FQj z#zb_h?SU;0Khug4cW7VV3$L7P7<6^LcaK!cNg62~xBwt_f-2CQmZx08Eh={h>Z=RKM>SMOt zad9X9@+SV&ar_~X-8G*?y&km&OBvCm0Hdd5Si!A(%Dls$sTUcT8N5Dp=ckP^rw?nQ zq&|IGDM)uweTd%r)MYzExPHbKTteZ?`nD}Uun`cxHlz)FuEv3^K*c~NMqK~Z3j)80 z#*LJSTzsKWZ6Hs%Qs7+`rT@O=qhK6#+?;$GM!Dv6ZcHr26x4lG>n5Cl=Q+Z z4hRbF4Y9amnNcRjZhX^arhy7dVS6zYsS&92MmlF`bJ9zrv69AftHQMLP!^3|(->i# zaB;nXuV%ZkqZ7mPPccSB?0v9spTu`*hRH7j%xgST>o~;lXdD#gMHiw#$jW2#9BS zd-&Ane&1euap1#~Xla8R47~_If0^BN4Z!L@mDfJ~1LLr;k{j)N_mz)C6m6Y<%KlPQ&rwZ=wze zWzDI()c@85=lN-unx{^3=S7ROK*9Zaa66m=EKYv+&i7@!Znw8A6C5T;H8K$wM_&dv z->=12u98Fwrt@?hd0aqbHqkjI-s3@zzMhc6R3U zCL|-!l?gf&f9++lf0x^>?8_YQ$i>ONg&2`x;<}qTtdFBq3?nA4ZP_NN-prg}+qv!j z(}^@z3^?!HyBRRyodMb+B>a_gtr4`u_FGz=cXU!v*6?@F5XvNIZ{J-P&t9a(OoHeE zcq&9y&877b0n1C2V^>xMVu4_Ie%Z-wXhdRse4egq z{G{}|h{T~IsDH*IK(&y5P0NczTb1`OFVe_;KFaxcE<7Td_o+<8h`t!eOt7segDA1>l8@Op5gGY{sE)LVxY&1LMO_gHpB`9h zwo1-N;{2xZpFCO23^6Np(=O>l?7t;M|4QYF&4Y(xeI5bML~TP&zc-qQ*Dq#|8Y#;- zg|9qH_7RrDHtTkdirZPZxSG#pu{F4k@9uucb}@iu#=;-6ThaoMTTqn|VL>f=CPi9> zXn;$Ri#8}XQ6VTVR1Q)kqXK*3=eNrILT3EKmoLo~CI&GtJTwHtqX!6ak+i%cjj(v_ zWxa3ilYB|4^4~!%8(Ob_x2{p}6+5CliDd+~&nATlzvg%Gl?3XH`2 zL7&B)cw8qTjPdX7jLfi?jc|R*Cfnsceazj1%3T&NA$jJwzqNshl*+@ER&$bVb&CGx z5WN>K$y%-@94JdE(}kRnB;&F&e#XIj94RFq6(eQ+kmjRp7KopFrdcfhUeqB~K{f65 zX+Bub>rNFDBvsQV#f0eqwsc@|*^9g?aQN>wowR>cVlIvmwzB0}Q%Pf`_AGwleHOpe z@Qc!LZ`nE~kJs$Kr}Sij9ij!-CPgUo-lT(Ks4>eJ4#n7z`{&#B^Yf#pL68?7?QY7v z&=>9%)03(Ff0@TUVL2~Cy_N`Wq+bC(dR5`%CjAbX$TV{3=5gfcTRFtJXJ{+a$0*Z)`Y!TuK$fn*QU zuAbip3Q)CJlzp-k1S+8n?zn&+U!adVXjqz?TfI6j-)K-7_oF?UKmGV2j+|FzD5Mnz z$Z)BgMM9f@k(ZZ~7^Q)wteL?}(AAsa)0sp1_9$Bcb#mOEu@l>?Fk&-!9QPMtA`5(D zl;aN(pAQS{*gd9)W3C@E67kwKke?flOiIV-mpy3KImGe&Z^up1*|Ek87Y%?RuP!G zjt1N$9!${*VWj%Bbro-J7-&e&adCY`_iid&--sw08ZY`U06DoS2AP}M{R=_9I6RhN zd7QlM{clpE?+^BHI5Y9jpFiM%o|39e3=EB4QfdlEQo*$V8H5Q16sJDX(gzg1N-}Nq zeit1LS=h%NZ%Shgx3*aQ=L6&86FI=T>5P?2h|m0x22$|Q)aSv^zR`Xxw(xg|GcqM? z%SGOQE~vruT}kQL6NDUF+rdL?!U%8bojGP2#U-pWdxn%4{PORbY^R<}4iy)*$dd$L zX(~T%VaCFnPe<^Pu9Kf_X7n*>d8vZWuT^T~YL{Ab1yt#kd@P6*W`AU1f4Cm>x(uJ1 z`X8M?RrZ!)7(0+!{<$1~E1;aZ#zA}QNc)Jc%tgjmCAIlvnIsY`vI(ZFekg#98`AK* znGa}#SOE~XguP=L6)g|r`065r=P|)4W+k613 z#?b~w1%dIGH$RILX=7Q2l)5h_HumLsc0&`*Rh)R37@tk6qM{w-M$M6CK%;)~MUBuQ z(1DYCcxZe(VMRh+c2rkCk`BUQ=EA8e%)B0%hKjC(jx3o~tWJ~DfbuE?)%C(}ds9|@ zB5m-`_078J%@{kgWA$IN8{=CR=_&z?!6$+%tw^!AUBZD6!t=}q-mvvlkv%^&>3*%D4_BuDw+h+!X5Qf7T(C_mSp=U3n(uL8_6aQQKiIiWWEOZ{`rBCt8dr{+zGk zcFy^<6JzvFUV;#l>UKrtO-WVcB@DVz-_!LNrZBO)|Mn3p?#R2M0oxbuO$%`+IA`_R zxQRX}uwE_D_s{e%85^QvySp*5W)xLFOA^>HO&($-gO9-L@+!tK6*)2^WSW>-ML5q7Z;cR6x@HCejB$Ue!Z&K za5x=@^Y-o;EF&YU|?Wj zU}7oN?U8C~x(}X6c13N~c-7mKH{r7o9i!VQ2keVQ^kGea>Xa{X?jOg3Svmhf6;lWv+An7E%AnPV$m; z#o~Jy1@K}u!+XQEiv?t8Oi`}awilY9F5x+Yu2y?+-@H8KFz2>}E`TWc2kNS(u1w0vqVFJj}Z2KA_}RO8tw zKH|}!=N_2D|vXUVsF>Cv4Y!p#{- z<2t9o`-D`tlT;u5j8x`Qoa%xku+JMme2(PXLftztxAuZ`eERzV3gRSJ-EufV&E2b- z;=bjiFki0ZLxN_q{60~6pK~e7)brirEd0s%KmU*L`98_D znm2Rkb>7F1TuxhdE>zb)R|c$XDP99~>r79BDCb_S6*gZshe$5(5{&yFNTTMxIm5ml zOJirezpb`&5_i%mBktV$-DoeWTYbhNBSj+z^3c8zmr1`;zX342Z7q11zZ$<$*>aj{ z&|-sU9$2$(x!eJV@aJ9OHeEU2`}{Z01 z2fLkdxBU2_giHh8yR2i5w{}Tk8Mul*{C`dv1>G~=s(PQU+eM) zEQ*E`t;v9`88bM*H1&SeYr`G9EODo=?6T%)P(HPie& zDUC8`u0v#{G z1tg~T-@V0A(q}!2IJo<6o1giXiN|C!i|(w~C=be~R^lKd>(#MzQaJjub|>(RjI3op za`-w|WpXt<77sX=oWrktJGxc$~6v2RAi`zKlM#GdugVbmPY5e(8?M9vW5LyjwgjAhjE+*Y_UvP~zoa z;2Y-bI3;mc8os`#laJ+%oA+bP1MQE}rB8~#`@3bQ*lAMM@t&1`B9oK!Chk^YF6#&z=3mZdw1YZ<~R1UJm$)hqE$yjbq24eF|c7S@6B-D-->wU`#N(f6UiQTa9P%kM~kJgDn$ zK6Xw(qn-i`u&s(!!c{*Hk zzqS8c#k>E)n|#V2@g6zLzkgf$sI(M66Mnx6Hv>aR22@f{qlU%tWO zzPteX^URdax(~_%Z=xla@^UFr8y({eUhH zdNPlnoH#zwtPHG?X)4utsO;2;3u0GMeJAZdo%uIs_G142m-^Vle3XYrH%y&Lcv$E+Zj5N&+Zbq9lx&LVEYQg@t z+tv%*Z(dc^-GON=hUz+#7L6xrgLyJ9k-En%ls1@_By_*qem%0Q_263fYDWI~3f!Ge z@vnO^XvyVnYMPOE!2$&QH2)(?I86`_Zn)+@)ZbOT`K08KckMmWn|#5eKM7(nXlC}M z%(U+-2T~Z zF5Nz|PSOGZb5}9%!v9CqTgFAvhJB#3OD&nt zqDXglmvlGFo_*f;J?G4a`MAH?nYpjI?(1Ln**^LkU&6)1JdaW0xq{4~BoksUmA&v} zc`BFn1}B)!{8ukSCj}U);xB?ZGU=BhJ3?YwLt8tdik?(v9#<$ zdH#2s`LUDK_Ikh60Y09)Y#WK%M@KhyU?K%YoSb;j%~FV{3Jr&`P*{9ZaM-muMn14} zd3~AS6nxw+^}oGLW;eO6jy0++QhkEhO=tJ>89-Boi()QiK0A3@As>tzE8>}rq6&D# z#=LO*vKwHKJxG0(JGG?gcXav*WA?G_+T^0`=K>S=QDuprAfm}BuNqgH5go|U*0pI6 z;G>Ix2mXy#>{Z+7L}{|uY>9K3@=T8{k9bo4lJNb1yaa?Fn& zRK9riloa1lceHo;sx2CwXgb{^7R>sB%kB`#jy>%?RIAH3e;GvB%dUkFYPHt)8x|#8 z&lIR*m+wrsI+SA4BfIXA528_Gh!MxS`dVk>MWgrq>AzCa2o4OIX_-SqyG5tA+J5db z>pWas!9_)MU7OD>KI>?qBA%zw#RbEO*VP*zF7h$u7I85$a%g8*nPZA8kOOek05Hyb4iZ#zrOA;o&VeOrq(J2rBNE_$^4(+#= z07_I$eA$ph5~CuS;wJqz-O+9I%UcWZp&Z!{dli*_=g`6_o^?jnUM~ z8z<9feR@~xkSzD}qwocSdivcvxNH=Fs!>Cj|5K;}SpPxJjG)65P?}q6QVsEHcx!CFW>UGfF-GkUV0jRFL!s!%lVixWCN* z{^ZEQ+rjUZ$4#h?TVjGD;i_b+-&v+z^Vg@m5>|xM)u_~DrR-pCGwFcS=-q~_lOPru zpy@3aq9;;k+a0;_onf^Sfi2Nw<^qnzYi`3eDok=uy4PEv-vK<; z*@B^IE-=@@FFcsYOgCF$*1{6xPyVORk)9LT?k|KsPau*5mwhIIk_38~C#A%hN7dp0 z1aqv7r%JwVHV8%(127e`eM0OOOZaELK~U59>_mX({W^Ext#c@WR8~h{27%6sn$gE> zRQLsfSZ)wh^C>o+8o~QQ&F4A5`y5*70G0p(HP7UDqfS_k$Kknz8geB$4jKlz|0s;>B+#_8Sl}TNzksIXrH^nL>(wM8d^9 z116fTK`v`4a-rTM2K=V*ptJpbJAY0V;y0>nB~n!+O_5LaaQq)SO+tp3>;eGT`gBY7 znb%X1&rcKb9y^UaKOUXKo3^eI{t2Ovm+@#hy+)0;gb!<{slqGH7azRWelVh*K6JfjRwQi8gzIfjh}7Kl!*txi-w%8N0tyO+*|k5fi;nU=TYg}NXA^v1^+ zQTDUv4a;73d4>5|CV#_;Kd3YB(Ig0^sLwwS63$LrdLv@d5ra_zx03%h=;hES&M$sI zA1n~aQOl=VenJ{6*vFGUS^HgidSQqb6^*Iz1T`r54>VOD{i)aU_Qi$6&1|{@6H~|6Cp*;VHC2xz#c=&EOCe}jfBz{h zD3!g=s^wU5CI%}Kf>@cBFtE5_`~FUs@7gG@_DMyuxo@JSjfmfTBVJE;D^$RO0$W-T zj65KK1^ta*kY}N;YcMdGng2P6adfIJ5Q2`LV|pzC&_WqWy!fGoU2w3>CZT7tqRN&i zV*q{Vrb4(-15YDyVX*`bD^px$Bg&NeLBfm>*1d22n%l`dnWmnQy`&QVmslbB&LL*e zxwN2tUiU!d#B+Zyv53?U*iXqh`O~TWA5O{51NZtSxqNE|OxL5stfM&Qg2~21NXS2D z9$g=>R=5DCteIh&DoP4rk+)%~?UrY~nk)~O`!i_&QOzmaobKolk$g8si=$is3K;aO zm4pCRpjuu-2+RiC)ldM#&)64TVIUWJZUKF9<$=F)aqfuxpo0Mjla{|Z%8Nxz+2Ee9 zPhLM>p0C{X#lk;_VgU}BuV#X>51fQ;0iB@@QT`L zmw9=?qf6EArs?}Yo+I4N@vf&KqiOQ;y7*Z1WKe^2<&NKTTo22Qjt~e7*jPp&H?@#1 zhgI#>o>8=dJFrCL-CyFXVJ+`i{SQ)K6+U149%3zvJ{)HI9q|m8al|U(_p&!Sz!LO1h(Kj!yzRUx<8u(aEl1_A+~lxl zL$O_7yxgIe<-*Cd6)1Wg1kNRp@87b@6gXRt|ZX z7*iSk_~SG3)0DL?fgMLU;_AjO-QS#iY$JR+08cNiXo`4+p7SaF*mc%6Vwm<_3aXW$ z_n5LFwh24cd;aRwiGoeo~ku0CHQv-)9z&WP?igNT|E6mejO;jiQ?)b{>DT^W5L_ul(%fAOo zsdUxdp%soBBF+07rArJG)T?XL=_z#zq0zHDlus^aKs)g-dKEoJ{xK$09eEo6%`<#3%?a=?Y()=-78&k%UC6T0IfLe=^m1}_;wEudSZL7s7Jg7shc~|t< zD|1@}nqqjowuU+18?^3)!?h3qlL>?oikSM9*0`Ffo= z#^mQ7E!Iy%E^+szst6HxHdt^djS4I#@jJhxnEdgZxHb_OqTK6>qkK;F?O*fgLDO~ScRzh)+q*TDR{mNQBD|=3 zOkH&>?K-75bRL|d_0!WS7oNii5EzCSC=&aVPtU;}wY(_&tQMyrN&C5FzO$Vkk+3^< z&aG0!t|VIt8*5=0`W~CTEPQ$vEta{UG*M52jte@)mk6jqAg@i6sZ z+s@s!p7syT2XGYNzy<#o7l`$Iuv5{gDo`g@{PxDh!=BDaA0`DS(~Fhssm7vwWqqew zBwjksKhBWHI=ch{qR`x_7}*B@iXoK;8lTbT^^9Y>^iX>+zCh~;c|u9#NZwOpCNN1IhptE%-IU5mrrtZJ03EbI?9kG`@9%}^7qWd>;keT!EGP9lE5@Bg`YrJb z@?|H~FQJI8Q~vi+D2?w4?b!Lq9sH9u|9_JC|Ev;jV}{ih=&W^^>Dko7&U5!Tk9c~-{0O+QnWN6#Xd@nhv%A|yxv)>Ksp&?Tk+ zI8C>1tp}HEDd|u@jGDZ-IcK=ua?V7E`Es{E_*nH+##A014I4|3&CEz>&rS$h zIUFy0b4wgX6|&C|jG;&{&CM;zD0?DK!*>4_LOD&GeDC8LN2ejW!m&RmN`V1I_)mBU zLnT0Ds@5FJx$nYyTf>t0ytpf}B%*YRrb#*oK~?OPHr+eEZ76q;4Q;@iEV^A@|K2Mk z6>)cYgXI4+&m4TSAT!KJ0SRL{b0LbKBPM?k$(C<<;MUsGo&vz5lBhP8zNp zzJL5OLKpgii}1b9q8k;eX@f!EeC3P85x|Zo3|X-ax8giE>}f-`OK_R^LG^Y1m+Jt{ z{E1KUX8An?N;kT)t{PABN077RgVQ5nXt^#tH$UHdZtpGijMI5jK)dH3ryznhG2boq zCODi%G6y<>!rX*}U;i3$+P~7PleG(WZsL2>SkuyiMTi>8dwboTp}Bb9ZM(X+#Mzz(_`7{Ox*>oNU6F%eq#Z5KX}XU(YB0 z{;+YHhMQ2@E4p$2ZsyrL#vq{JH_8Yf?Z1s-r!qzlRg1$pHQXOH6wmztdk^Sv$L8q>)`xh3d;~E%ZSQ zg;+q7;R|RnE7ZcC>zNQ51^D4)fK?jICtG%pJxeAAGep zXI+cLJJ$$7`qRe~k{fjmX>CN(rqLx_N))4R!-VK(I-n>R<)PK{qT%sdaRcJ&&g40c zIlov2t5voy%KR~Df{)^VKUi)UzoBwqqBk)cjyO=VO#<3@u=KcyUm{yFs(uk{eW)%W zd2+lg=5Jd0eSiU{hY+0kXI9=yuFK7Z+9*@?llRBIge{>N&X{M0Gl#poOLg9j>Ms%% z-QC=_4SQJg_8Z3&mwO%9|C%iDyPAQa=w^8U0mj_`f`T%p;VH^=p%h*n)1gWn_aFFz zg|ZKu*tz_M8Y%6byMJg}YJdOIqNfgJHq|nmBAlL+HMW}D3oEh6dU#rrtu?b z%n1W(?Aj#sp5xih$j~z-^Cq8}^eH*50v)dB!5buzT_1i#g^7uYZ8>AS2jX@-xkVpO zYCM)U4(Da86}i)l0Bkjp3j*bEDKJ0+4431eLBi}D8IJi$j#2CcSAK)PueGXc@#+={ z?h1cxJhi{2R@G|UuWaEf2MEGk@>4F8ik^rcwjD6b1~uG9*^^U|E)&Pz^rpgj_hf$S17q5(?e^qmX+H;$wP5;4= zfM^vzq7lT=`-agLfY)e+C3>$x^5B$H`ZOm z^`4d`RY@eo_yxs0Z-c)$p^#Lg!|;zJ>YitL;GjZvYyh>_?6Z3D#dJZns>1csn}Ol6 zkw^Zc+A0iU`&wV%9Hrm8!nM|^wXWK|tDF#gL8z~hi`?jM8ZIt3YI#m*w~hO+p`=Hh z=XXO3>fhVzIoPQzxk%R*Kk2I{L0KI|_oPDN+;!%~A>C6|;s0*!T>@XCggZ@SafaU3MoPi|1TO2z1 zi+?7Mq7^RPC>Ms4KQ0T*vz_Z(r!Khb#VH($Z~AJV)A)~gTY5oIoX~gue~}UvWJM~5 z@RKaxm@sHgObr&gnpEnFoHUfFaABzpiBYw5e8SKmeqRtN1bj9sR{sH*ws&g9UAIOg zIbTL}%F2ey;hJwb7wWR@I>T;bDt+3`XO7GQSeRH@Qx9rPR=#sD`z?IpcJM_-MBx~n zuMo;hqg>#DfAi=hbGUH;@EQ3G>)nj&|7d*whp4JtwoY+c#SYMdcF$JtNI(!Q5IT%r zYE53@cKIln9iOQ3ge`fw-Iy+8IOZu(=Y9Rz#1XEEE)99ZCw%rtiF-Jc-^11QIwm(Y zl|x?}Rg=2DCiS1U#>dC|aLp_%uohCKHT>)HM7x-D?{R{_3W(+(Xn~}OI`lj!otk4OCM~)!q(D@N?`redkv*0Dp3CU* zY*p#jFeWT1PqFDML`X1oWXIW|vZYL^^lWyvSGO7n^Okjo*Ph=pXM6hWoD3Vago=(( zvXihqi%s%*Q1yU6+>0nELP>y^|6qU`ZQiISgv3G0vT&%ruX6Q&8NC0U`Rf|>-ZgO<=sX7sG*}fhVs9x&BwWGzBAH0-r&ftQzt;4qb ztL@r%{f8XHbnJo2h{4;K!Y5akWor?Y*x9DW=31%$j*Bg}_dOUOU`l{8f&-)|nRw*U zA)9_`GE`8hTG{#kk4W03ks7?ey**+wDi~_#@&7-$p|54vU?`NlarzlF4g!Pbpn(8+ zT<2W{C~v*nLMI%#G<(j?E#`?9uZ|Pk;nVK1Gn~3JWT49tgQ8m4JuU{Tik{E*BWB{% z2T~4-Nupzp`nJw+ceq}V1V(Oi``J$%8XPw{eq17SzQ_G@{!wLb(XYn|)qpEO(8Hu6 z{o&{^hah=r$m*N50T!lg@2mggb?yv)n+`9x{9^t2zGfsUCi=CYi zFYIZsWyljkwN2jlD9%>9QD>(MCT903?f=RI{yT?5%~cJND@fm=lwvu^-HhMK3YSE^ zgxU3prXc{8An4GUm~VL+R)Ti&o)#d)4v-E~jL#N<%}&+XA0tQyO-^QsV{vo_vs*ro zWEqKsc;HLuh^QBeY3*-FoL*meRSj!`pA`ZKHx=>RL^y@b`|j0aD~oD3q_|N{{{+cR?ALO zhXlZ=#g@9(=+YWYyFg{KJ+jThEjt&(oT=RW&UCGZf(LnyKPOfwYDYz zL{*y|{Os+eA*l8O^+pYBjsHh#NF7M-??BDHuZ)*HHhJ;i94QGRhFzR>*{l&&GX6R9 zgoL$XfL8L^QwA{D^#oo?X-bdTOCmUFWh3@JM&gw&3&MT_lu_8ke=;qpQ|z4jQI-YCluaCDD>9fvJp9}5t|{{ zaTbC8|8fDo;b$#nTfWvLpT8S5$?`F-6x|B)6=5c6!T^$~@g3&RPOi=(YD`=ceP0$Xvx{;bRtI$;GiGI0WL9EB8vRiSwZ^pcv zabPX?*;#2l-Mj@qH4(l#S$RAb@c)8HC&nDqm)F9vn01?wXhXaNU`(Ws3vdUjhrU#} z|IWq&RwTL#(oZh?G(-@-U2@9>n@5a}z;826mhKnHOlJ~wTJMo<_h~3clmI*G(O3*x zdbtPWVWykUq&)IQBGG=jdFg1{s08|KUW)bT$hl+fi22{zk$VUA=N@dTqoX5ZLnWoQ zNsEOkdp@|tuLTFC$Yqxi-)xg*?vH}slwb1q*^3K9zD=W}Lm?1NHUWmO&uI5C>x?J` zdHA~j{1J_+mgcCgt{<}%0AK{_Y{~i+vW}yXEDJf#1`Z6R&8&%0k$UWZob3)8nMkr8r*8u$uxZbibc*?Di6Qeoq|b#T<~} zFknM&aOW3r^OU{w_hNpj5D5CV&t0Ruwo(SpsX0E<<#UqHZg0E4pcHrUXa(s8vN7=T z${~dmpWGb=O9&o|dF`215&}`*c66c+L`)aE)Bg0Q+sljB9d`6Z3T{Lo195pNaEWP_ zyyHiFN~oqS+FOx4TIbnD#0i{@HD-n@?dCd0!(21;FOk#T&nRCzN~Gp+t_1P5;Dv|2 zc3AQ__=7vO;?Ddaf^|gml{0Lv>2Q{vNKZOgU!I4^irx$2#Qc^zvy>z zQx}9hDL5U0MIIsBKOP<%#ENlqT`!tnqF@NTJu#oPF_QHA7aq2qQM_p0*Sibeqc;LG z&g6sE&KfHP&;38AAS6JqH@n3eX&iZfkK4!<;ZqHfUMc*gB{QS?8G!#;8@p_&5Ld+}5ffCp2WC}WA* ztb;=eLI_R6JBHL^F4gD=y(*h7&8Mgzw~ly%sn3>7L2e%IY4}6)m#1<-DHMvM`}ZeD zVya2W#6C+vN6ri#l;T}=opMUToor%41Rh7Gjy!E-AvU2D8P6XGq2U{;aNm_lo!JX+ zwkmK3SxsT(lV;{Jxsm3ioy^71%U^ zE2AOi&*}2ip8=Vz-s82MbF1UNbK_iIhA-nbX%(!u0Y`OI_O@|0_GmmT-K zj0frB_qr6<=?e1Hr9snn3l$ogO=>A;pN8OdPP<&8td!v7&py~Q#3Ur?jFN%POLmfMigwq-t>qaUJbwP`J0IaQ-+m;anzN3M;vHH64MO&Adx zBRw&pc$1@X^~iIX)3|fyNzLKNUcWlLhi#V~@=gzF6xMi_FL7V~qi6fwoZh1CbY8m_ z69njp`{~hr@m6{!_`KQsJ6F_@{}(!Af<*~G;}x3ALsAapd@CC1vayig(05^eZ9HtY zog|R!`0uSUm9}B7A`lQaJH1rpg{U{u51!KiOho_w_XN1Yd3(PP>hUwKiXo7^`L_*= zj`ok8=iGY0ee|Bf9Atn;hc+VB>2pd)v;z>n}XI#4#m{_5+Xq$Qt6 z{Itq+PM-$(fOm(6Gbz5R>QPVZ5C+iC%fctBiAV6DAwr zOfZead36yK#;5fm(F8yv5B8B;FH6jl_!VixZVw%VG3Ez zS1tP4NdnbUjlnoWLL^EOusJc%27Ce+Hr(pH!3o^p8HyDbqG1E5w>i|Vn4hcs+xdOq zdcu<^HpFdRnwLo(C%b~;*Zb(BZ8G)<`{Q%Lw)GEzrE%4z0yp1Z9|h&IFh6d```THx zlDFHdqpVZ|TZp29cY{%80Dktz8_!qd^cetC7sq3v?^u9ZT9y@Hk~`Y45SH~PR9WqN zhrj+K^7siAj|@2*Z1Anfkw6C7Cv!iw3&$7-crh9a3!mxDhpGdQ+(m=fBNxa1=}T`r z&Lf?75f|8U(==ZDms5E$%S@!*n@eyqZoF^0#hEO(XJ7eS92>GGp$Y(uZg;X0OU+!l z!FFrQA26-^rttEX2KdRvy|vqwsp{Ahqj%*?y}oLTaYY+l!CMC*UZ_8!&M`43eYl+_9N z{LkS-HlBNWBcoL_ZelFf=y+@Y>eE<99Q^Gj!JD99kt1OQ$HXXOqn$xjuy;|6_jrlc zzV;BkXhDV}NS6`(Y74!Cj3AsqDaC$O^o$qtD-gs(tBhSy_JzVaoe}#hEsrdEfOV$0 zQK~fd-w)xMZ1D*NP+D3ZOY{O1)=Yutr3kfwqLJ~-hFFlNSX^ROctbzGw^dxr|00dU z({1<~3Wd~kfa4&b01$({IzG&%?hlcj_Z-ZJ$MKaNhzF22LIi%zQ0T~ATWh~)NQ|ZN z<$LohiwczK<~`HRS^T1PipV*;c}W(}j)wMaM`_jzUF80nhz$i)y&+_Um9`v^pMNpNZYn~H=p}JqR z%=Ur~i$9$0H8|4-aC*6|S5@>lFqi7aYgkWY1-3`H^C@|Sq%pm{0|T>l2DN8)Gf85& zDcNDD5YmE5!cSQE$7CNrsYezbrq4Q(0#FnYIP)1QW>s9I*>fRWgtd#-4ck%7)Vlbm zqPgFLx!m38;;D3)gLCNQ5;;yBmQ*7V?CWvIj){BFDBZ)$MQ97$Yw&*m1Bjv<5%dqUoD z_1LuYXM#hF^*ZK=#}rEGPfiWDSv;VmoA9T2#)1hL`gqLE(nQ`@WiCv<*qx|6d@w)W zN^N@ec^ved%q>xyvNfzBanR)|OI#&N5}s^Yga zn#;`5b>CeWVAaz!pRv@1VW^jXKEtyS^09W&(RfyhiyLZ~!;8A|Js#7~l*sXiveHNw zOe1ulr5;!N@|266)$hW3{a18=D*2F}$*mFrkm!B z_#&u{dROOs|CAE~KqB&FwCJ$-sMw~XpYxYnc0gvCi;9x&cUPPH?LZy#bL)Pt9LZEk zUkcA~LLk#`JJpRjtMDT!C5R>Tr}p93IuGt;udLi|_1J$7454)wKXiY{S}nH6V*=y) zD;zJVKdJ83Y-C%plqxDtthS5sR3OC})D)3-OCeXEHtA$@{9Qiw^o7a_QN9qE98oK` z1fXu7r=tVF>a1tq1LUa4r}l$94L~sS?dqJYp-1AK5hu#RfRV?t zod!m(;T!kR&ZNr?sjg)0-p%F3i}U5Q0=#4p(6?ykPR3W@3&R8PH1W0wI*8oAGQbZS zZ0QR6hA4f+YR&rcKL={V!N<()&&-X?Vf$KeDuOSz`<#lix{eU4;?9dZ&6xJ_d3dDZ ziNclOM1mizV5&W(8Ae;8AMwhIGJJFQG2jj zj56x~DgqyT*o~ope&jTd;LFa^7u5Mw_d!}WT#ZhPMFvuE^#MG&_`F}Aj+iz#P|MRZ z)z5p&RTMKvD)ilfPAqY3IfCBk0RWa8v_Y9(KBrOCPIv%q#K%Y%a`wnoyZV#0lr7Y^ zfVPU?-C0n=$NN4|3h(o^Y(#FBQDG^&R9+moPqSJ;OTXwE}?cB8u_**Hi6)jh69~!%_ z7zv25u*nkeIgP#2tc9)n2?Wg#PFFn24ISaOif>zRf~D+P`e#4@E5o<-O=9Mabo{40 z;$l9pDWM$bnV?Bj>ya~9?YcK+p>)NJ20&!)LA9KZ1E(a+*6EkWg-?30LZ zwWq~XLV3mHkBF3d_ZottZy9My3hR4f;Bo?3o+Wa5>gB_2&)Q4e`Az$U+y3^>KbBlH zYqv^aBv0#!&|v|*DGe+9LORpRD>u6MP}WT9+48}!7qi~nXPC()0AQ^yO>tTJ_xnO> z;C^Yfz{hRsUd3Dj`hba+qaI|h^_|OaV&&n?$Z%kFnrB`C$kEs-0RalE<$Y~mZk&3Y z1cDt^vg832H^>f}S!@Xc%Ca8?tom*ZQH$2qcrm%+d>u7yzv(YNnC6GNxDclT+8)=i_(GPPOT7`5NSw3 zzPH2m?~vKjxeB%YkSkYhktFW4*Nly^zx8#w ze)LeqnQdKY;U)>aq_nNGd#jTBB9Kf=_#6N2h=YU<#wDWtTf<~Yz7J!LXSMI|SRHEN zr{9bxD*uf=uGDibZJuqA4bTQ&UznLaskoxrv6Xb35w{yV=HJ{xRc!V+ zr!9BlRFDfof}Z~s?MEhB^bU$>GU(>}CF*)HAFbKpt`y+q_3nn@pR(rt;(|vjt*UIx z01ftGd#Qd=J2wig8ik6w4L?y&)(RU(M@8V}8jaHO$2}RJAmV{}AH_yuipSKU5XKjN6E}yun(2y) zp4Yr9{_B73;LnO2+ zF*n=IazQVO;;;v8vyMd)Hka><1BMLcft9tu4&Bu)fCJL;YpQQS;K}ScG*?|d_ zJ>2f7O~{wEVr$0OVwqpUW%a@-)Lm>8JS+J9RfB)y*PJ>pMp@G{g`3#`^H;a}9M$LL zD>=WbgYUWF(f?NS{64RKaO%ye5BMYaato5^Yrb;14x_`xd|k~9NP!P0!UcU(XP@eHJX1}iW3FA`V{%qL=weJ8!ttt~1# zn-?dg0JT@Q4ySPh?55T!w365BqwPDdyYD+W48W{dWr1<#KNYpyzM)9bhJb%_jvJ&V@0nJ7 zGFGOw;RS+b>1gBP-? zc3w;j1a!$M(~9(y{8f5wO-=(1Dm`g@_1Fi$$^T?Kv3ymX?_p{5P}PpVt}w zE%o(q^F{I7&-p3T!msh`iWU2tT}_&6Bj5IC{g}YF+FousuTQP=kRe?kwKqclI1gDDDY9Zev(9?gBWzo!em$J<2#d#l(*3abiI@&HIy3QxpR8{zhCM9tl zdWJkLz`+I;L4g4ZUSI%Bi&x%v_LPi{h%SoIH0qMWymv(D-3X3T?Zm$8sRAm0Nz$O) zJCOvRtnCX0<@4tp4Jo+6^v}&h%%Ww5d4=e%+zhq+P1wUZI2n@7$lHdY1oryc&2@Ek z>bc6QeR=17<*Vf zr`cWUHN%>}@CL1H;7fcr4~E1O-7n!|Xq3qBc z@#B;*lyc&!N>-~x=fzOn&es<&O~O?NqLi&f{mcOXc~$XXfet_lpGPnoEh0XmAnVzG zDMu)Q{l{mc?wgzS&$N?0K6I}V7mZAVD!QZY`sEYgaW9g*%rR2U2mKTCf-k6vF%MXl{$*5HLf^+b2aP?q2Eh`% zr$4=Lv%fu*yZ1O8?>0ZNUV5!|jgzBhQt%qAYxr8bn27{{`3}t+6QM^z<^BFv{u~5GP29$%Ku3iPB^UT>f^NhWjmYQn zdNnk9yJ{`y{Z&?C?2E`xi$|Bgd&Wa*Y*~Y=wZZ1^d80vmSw(>^sil^5`Um7|42^LF zsUw(ofnOnZIeLFq{rZyl4f!UoyA1eu$7?;kG($$(|! zcCwXHM;m*IMBg3fh*~cii62cYTl2QkGjozoW4V8gSfQ zcc1|9$l)t2+Pc}g?yc<#%6S~6i1NTb?W+hFH5{M=M!7K?0W6Asd7^C#i*|k=ksz?yj#p>{%ACrs#xt=hU zHLp1RwSN28ebuPlSR$hHqitCE`_#(umFHQ?%~w3wZT(olh`v^NTrf*0pwKFnxfX#l z>1q31BY7xMxFv$78qA@FK=*PxN!aA%rZFKtJuKDL`B$yOS`fxF0R0K%yw!!&TO)b>hlV;KjcTW zskCDYw7iFnC_V2Vnj&=^TYLT7{qAd&1e=F4$A%X29HIY+Hd%!;e(3D{Kz4H=%PZAz z>E#G5Od7l|+PCfY5X*^&wf%! z`NM}AGyI1~^~6a)*g*5-)GH9tn#d4pCl8jEMc|Ld-FG&r7JzE z%@gHX`_s{HGnc=2r2H@N!f$qop~pQ!C6-Y58`^IenEsUJR0~an2#9+(v^IfhfAEXC5fPfV%0Gg|PcVL46@k^c-`+oH#4#n;T6 z5EnXkC-~xZ!8ZnM0PJ$)Q}d3Rr<;r}3Wi>@A%WWgCV+sXAm-XyX?~CP@BP{{Yw~Np zC&EauvE!R{^QZnDQXlfl>PLqFLxA1E?01Zz^-C6TNIN zo9)hQ-v_*g@kZ)B4`j3*9Ly4Dy3&#Q$c{!^c4_>x+HY_!KlEvNMyQ|Hd%Uf^Ft-MS;v4B={HopGp@vH)TuQT&@}L(XTYO z$Q`2eN;9#EpB+$8JL*F4V?A}5BK}MIgsMzqSCWO8e!SAJ;Uv(m;kb98?_`f}SqD!x zUOC7`Q~3EZe~dc3h;Y11=g3mvNxOSXN1Z1%DNaWiFYHr|Q=-05YRN}PxUXjep)g|d z?vVR%eu%7Wk>6@zq=i293Ez-s_n?T5df^(vxA1uv>rQ%I#+8Ma%&p(x-+v-LORq*; zYAmUg12dSb&c3BT)ojXFEc$&t6C$6B^0Tf{Ls_vsus-a_CaS>w1keDV@6ygcsC6?H zu>g5{3!_3U%8?0?gk!@YtP_WYUlDEzWB{~myxP?0_R{%dvYK-yP#3JXXfs&6Hb$MQiwV z22j)@_mN3To?^1PZUR5F{_v+COW0#>J!kmYNBVM|U5WRd(Y*4u(dpCquUuG(SS9HB z9c7-#K)z`qvWHvb2pK_X7yvCv{M*zjJD>A|QwEXLOmRc+!3PiZ#s9;egbLmwa{2f1 zD?ZaC+|`oRlys%_#}tZsS1wQ2JZR_oU)yX*4Ya%V+2I*Cnw^L|gEW5h?``dW@mZo2 z9VNipGX5OE7%zlIQv{JF4x-~1+xhofvzoD8|EF3mNmv&n6Nz59g?7S2>z~=iFWv@B z^n{%}`W4ICxvwb5qh-sq?KIiynj2X(Qa_EBM0a&zsM2VpqkQ>kUn)eNG4)ZC&M?Q7b`I;$NtEpM|3QG)rrP##{qI(0Xjvv6LW7(@L+4p}J(wr3@>2>gf^ zU`y635T4G)qYfMIu}-l4xsxtBv6#P#^xqf0W%W@~xtGztAN%MFyJB}W@D6%U{StDO1dSf#~2bQrmw}L!y@gv!! zYVTyKV?Xg)xj|S+cL!m*@q$`%;nT*Kzl|eUm8Ll>gr|ueHrVe=zcjN&{)jYUhry95 zvJ&;#fh#o)(~*~noPdgEWC1_+4r6F`ameqt@ooNceG0&ZE<(b`_$Ey?aWrr(ri}+1 zeQr1AE%^?HPx8P3)Cai%Az$(SIh>MF#i3sE>B7;pMI}1W8mB_9=yEZ?F7O9x^GifH z0+Nu8u0oirk^H^+EMBIuw)iTbdFN}Av*V}BJ=G#LYk7evS%>uvd)z-!jp$)Tmqp>2 zKK-$bX(J-GdOF-uHQqkH;&R;Y3^lc5n8f0B#7$WdFIZ;p@|ys#wk+QHVaMLYv=k4} zQl>;0-jF>DnvpM7GAmLEew;c;VF=WSNVExVR*#Lkd0AJcb zH8Fw&`t*1su$ZlP>gaQIn_fx6rd+*K^pez!?zOb~*`_Ny^*)C89Z9|}7m??UaRW<~ z*%MvK3LicxK?=#K&vH-&HR>x8m_f4=ZEP}<-o<-gd85b(s3xx3KeS0{Jqk3?)9d3< zS7Ory02=2F=4$@6h1up~EtKVPTfUo7*28pN`HP+JB<*e5xw4rqaicZmvVr>-6Yg^( z?{NT`oj&4>j@I%BJuRbe5yxjM@jGhR*a9mW`ZOZ4N;yu5f zSHS7XbH%evN6H6bx$d{=rdMOFtUB|Jp0-0>t+);nP2wg(3Qf-?wwJ_5KaQ^>$`+U; z|9llIww9-NUSCB~Y>t0)+=P`=aKw7|Or!j<)!bdCij1?q{$qA1X=+npo@D^7uG&`r z*j#tk;6*Il%WpL4P61s#qJJKKtbX1xusk1}c6IPDlv4e=`nI{=I$ZeXLdSO}lMo&9 z1)L=r{&{_23imDlBeOOAfy@9Jw}5J=K?+_qZKfd`(T=LY=8Vzii9<7PTHEs0ht)GG}gy`kUMxS;RKeyRWId(ONnd18R5lq)Xo~S!LS4Z7gCFZD0aIm?u z{N(($!rAbYn`_tHAKBfqQ8r(16NeYzfYf(3;39rPoR^cp@HTW@xZOS8LX=OLb+jzv zta8z9n)k9ELgBnP*DNvIbi3Ac$_eE^11#TeceD+B)(Ct>w`w~uF%Z`lblz*s-ua}v zcrE8^iGHH-Vy}1R>8HOQTX>C8aXF+ovfunxyGwn2>1#w4d4+?OaxdYwJ5@S@ zMs;wEP|xPF`(?;Ko+*^d4{pVUkh_M5V?~W`BfEkRU5cdJE4=%sn56+#*aXwYA&H4C zk^s=sVS`EjUX+d8`S`ioQ(_I`lWqpUcH&M1l23i#NJ`hPJr5ZaUd6w5txb_Z@7pXg z5vq-SOE1yIIN!^X{2R%zrM2&F6>!y4)BaQ2gJs=8{~Z~S&Po(E*{U5>)qIsIHi9}o z70^r}8G>7mWW>uhq|+8^Tphm1%;)t2!3>IGKhXd!%<8;Cd4d3-rs^?6{?B6664qUe z)4DGj`xQ;vA|%k%6i^;;$@6+=Z2kgZ^c*wh@EjHn9TAz$ypv1jEL&RU#jG288z@5^ zKZ2H~e=k}-8lG)-EvhzEA3^+i6q@+0HrHpbr+Y*t`aFaoX2{PNdclasGCf&Sy0;H;3qgJ`p78l`vbKMa6x07bOEs4Foi}_9mDum|KEtvJl99=g9YGMZloSwyc7L-bZT<2>vnwV>#U6K_Cwf5o!Y_v{jn;b$C!{|8baoR3c)gDZkz4%V zHO!rV_MY4NS;tNd?Dh+B!;#?xgSqZ#kAvB)$hUJ4b^_VX@g5dJ`MJbxKkxqA$#mRM zn>bbzbd%gEAuZ$H?Z-%Wgmu1Bt8n6S-G$w80SL6uQalK~n|tGPQyXly#xQ=Ad(d9~ z>^%TK+J02--CxxcYU@XbV13eFCSS1JQ00@W>u&a%21wS}XWHQ5#*zV(zrH8Ucw*it zAWK5?fdkKn#hUf|a*e@5yiCcH(k+%R(nPoj;md!n#ADTAv3L-muk-Q=F~18B7dMC@ zSU>P9)z;|d72afe0x$K+?D(?22`X!6Y01#wU8i9q-Ieuk zx*3))IcOUm8xu(V=ca?f;DhRKkKK%bFovWMhe#SDW^ zJ+^{M#Og4R)ByT3?kl<&ccx4k9Kjn6?JV$POd@RZPM?pkE|vUjXPSgcMt z%6K^9!7R*x^NlToVl7Ja@6~YkPzkH!w)mTx+{prGC4*@sw!MN&qw22*?>D+EY)cmV z381*S(HRcX4n9mwI(z_7V~ZyAZptR7i{S+Xt&#RXvVi-qJk5T==HZ2>yxoZR{zkb= zH}jWql<;2kO#1I`#WUNWjEV^mq>{z@Mwx}@=XS@eWlDNhW*LY=)~IsA1!j7m4LYLx z5Yy+sC-Z7G@ZCEnSn1!RWRuY#oame}-5_$O@H%ySp?a0g+3NbE-L1FD(KE;AdQLt4 z7)_%s4sPVQhx^F&lg9_GwDbH{Ev|uiifMb4w4E0Lna$31giBM1jgIRndJBGFRBpAeZIMtJ&T9A%Z)zkOhrd{K@+=C0;jAU$IsF;x4i( z+BTL@2uagd#f8K6O)C9%KFTxCr5s2+Z@>QvHbU4MFU8uHTRy!RnfThG$3$Ec$E`Y# zP<6@U-Ft!A$9e`tuZ?Bs;N?DI!sN9?j3PndL(}pYsYdzjAb%auF7CZ_Gx4 zfExRkJ7Ygw=b*l7H~$*EAIDW;)oyJsf{v4flbnnzI|FCzNz}2tz8hv&0KwDUn=^69 z){zB+_ut~@w0&r~mwWS9v|FHBfEXDS%L;4xpHSU)mAsslH zl=!V|QV&&hQW0IEPb?)9tQy|UzuX_}J7sCchH=tmZUXQwq`9@-IHVwT9jw4?v>*Cw zlE>-+Tck#~Dwqus*^_wh#Zv81W`066=FWQ)v6xn3L-g@vbyRCQ?|j}a?%^>ch=7;S zj2Z3RjpWGwb$gN&KWEI^a_FUWw|#c7VQrvaxQxobcSHGmN>1*sWVHQyeLm1j25GUd zbYXiZa`Z2ya6Leo#p&UFDn+H_>4}Oid7v!rY=lwu))l}UfwEv<8qcfMjvj$yz&L5# zflE||0q8(k_Wnr|17l4+9A!9&8V-qr^76?GzE|B40Z?+v9|jn!1>CfN7vt(#YoQ54 z70h-ps{|FU*nI^m6uyviVdMJ$<~4A@IsyT^1Vs)OC^`94>CL*GnXl^-%prN?9rXFU zH*4ef$s7qe#V8Gtk^n%v&~!>*U~|hq+GX2Pfz|D*~Vx zu!A^5Di!q}3k$-4AEarL?qB6&sTRcFEwH;vmD{35S~@7z@qwA~oqolXbXi%9W5XmK zB&?6P5P4Rt!MSox0eJrg7b`DJy_zM}5;{FLAhaxn>U7R+QuLrSC~PG>zK!z;KlR1aC{iEKU*;ajApJb zCt(Ko50QgKBeERhZ(4oy31J|22XiLeAu)Agwq}PRxEO(@JF*(~#aV453Zg$7s*UYh z@tV6U5&&sZC`W?9N&rQv(aC6oL6Ne_qwj< zOZSCX)>)@)u3-H$ZxdL&AS9#zw)h)F%l|`I+JzL=6kbUktuv# zfgcxXbWy)@w0CKsCA6d*_1!~s^zWYK4Cxzr;k)DiTRL`ftxb{ssM~w?N+Z%NfiV1+ zsvDh7-=*OAZT8^JfmWNHjVSCV&h>aU_wo`%9MuzCdi#+*5kWOb&;RE~^WQ^a81BO8Fc>xDop=U$22kOu z$NWP07=Bh10^PSu;6qmE7%4s*=7FH#o*dc zE#p-ANK5G$^aKxyucH2?4}16+svJ6m34 zosWyTZXVr)m66~?!X;w=6#L#)ccp?iCNf`%@|1yeo?U+#pbU9tq)7h%$H?7-bbK5$ zrisS)k i|Ei+@g^T6&I}o)>YLqicFIHj&08KSrRg|(_`2PSVwSaa2 literal 0 HcmV?d00001 diff --git a/ros-realsense-nav/turtlebot/doc/img/screen-ds4-nav.png b/ros-realsense-nav/turtlebot/doc/img/screen-ds4-nav.png new file mode 100644 index 0000000000000000000000000000000000000000..5770927d3646f8ccc78cc10cf09157dbbac4a37c GIT binary patch literal 151742 zcmYg%Wmp_R(=7ydcME~w?(P!Y-QC?ixI-WTg1fr}m*CFgu8S=0viK$M{cL~iKC?5^ zU0q$>Rdwogw6dZ!3L+sQ1Ox<%%r^;D2nZM)2#8OI@US2M9L!=dW0Y#K10Yzh^l*Moo;yf zV=v(Tz1p%Lcl2eZEE0jw58LF255ZRP|6HbxLA0D>kZT|@81fmniUzj`zHGT}CW)yF z3tq6Og^~RtaYG>(<;Ra75TIuv0k6`{?Ck8xEJ2XrSAKdmad`4Dbg}>Xno6!IA^QBk z*I})7-;`DU&l4)-5o0ypU}Hkwww1kuJ#`B|2~O5@d5MK+avsX2lFTpv`!18StmL!0 zI}h>cW*bW8f}%t=pSND8DCD}H$}d$pJ02@lTS%1v{bAiX*_`&xke5z@1X7`}!Qn`7 z*c0c1$p1>^f>GvN0=zOC7MZ~?swMU9g6tB#K(wH>)|J^-R>=b36jPSbm<(3rXWh!r zabRZyW7ce~smZJr`nQB3jEsz$9X4d2>dnH!!n11+5dWv$s95>%&=?yy)p9LijL_ci zz1Ct*(@=7Qi-!Yv#LW8Hy9^_n`sCIkD3Be zG1D&{UZ+3u3jRlfVP#E-a5!h4L{!Yo*piWoGxZw_dI;gc>g^uVd!|lAFXmK&@Tji zvCcS-!Kbs3&8B@F!8uH37_8V~qFh=R6_h5wIS1H5J4 z$|@dk6&xHI;&b$aP@%t2t#_sh+=S;jycTMBw9fNP(yJu6t;k{rSMtvXIlV-*-MS+G zR{}A0#bP#`4RTtIx#>1G9L~uVrvm=pho{mre-h}e6qB?yQ)m*_Qu&6ayld!NPh=I` zt?1}zc+|Cm(!Q1aAN}xf5M}DX`|wIMl;%)SMK(56D|yn!7CL$tYKug zNn?g%#($L63V%e`9#WD5jm?QojEaL|H7(0H73LVBJb;`n7afuFH{dBpUy;8Ha3;GkcjZm1uvo&L|n z;f2Yf&3_^+LuJ9wq7cD*IMPy$=urL1WonC9531SZb3gy%Yy+ z0XSx??*4ZLZQhhE9UcvhIZ%ItLk|Nr6ffe2BMn2jxahwxdDe)|YszBV6rhyh`4>)xYMmS~7kWW1{=`yAx_UXUh|8CwQD2 zSsA6ew6k&EM+O)54$MZvkBEM-@w+oMqB!p`N7#g(l_XuGBjIcZsaX{J{GgMNGL5DQ z_n6H9j7i%&7PZ2|aj)qGr!b}xL(Wq_R%XFV_6;flrHda8S{ZDhbU-(|;ZH;^d0;Q# z`1+Q=>b8f*Wa#SW z8tzc7i#zkDbIsT1?5Crsa6q+=;Oehq-xy7m^xW30~y02NUp#%D#UED1h zl|EEK=0OJwm6;EvliCpoym_ywahDy`S!}8cy#%5}B8q^B#Gg$b+?FhoaNb#RQ^dHG z9+}A^gvRKXhE(?-yi=UTMoqJh#D(rMB8_swrw#wvAZuMxvJSpaf~Td)*okwR@Ra#tsUC^gwg-=w^cF>!2Tw$fd<3db?e_mi44 z#m?f45LR8PAVKzs2d|XuERF+%oTEdpSCz3nHac6S49aEn;WtL|7 z3E@4!1y8H%Q6SBT53WdiD#U37-~yX3FQb6a`Ap!vJmP&rYY*oc+8=y2OaPq_SoIRG z{_v-!qDDrSi{8-hNAw9&HXt5y-eEPRvX)HjnP$$Wx!SmVEoa;p8r^kOt>~cVp_yz1 z7~bIvdD-I?R2z)@A19cVEenma0E8%De^xNk_dG$RKVR8Jrcq31gX!9QOk3l>=EBW zR&=njc%?qu0(Kv!tw$B|p|OC}_yzm`_8j82pu%%}&xmeBn|Yf8`LqV3g-3e1i~w?v zJHs{45_D(CY-^GMlyh30M|Uui+N`)d+S*`VAt`{038x=k=1nHcb-K#@pBhl?k}#+% zoDrX!1#=-)I=GGZq05&$-h-ETv-{UYNjzxA!Rz|E>tkrnwp^~&khk8qFg3ASBZ3Xl zWTlGx#pS`Byv;D(3#oe+l)$lJ?*^x^6R~RJ%d0zoTpL2JXPJxSsoWB%cQuRZ8DdZ3 zKRXgU@r3-+5X6sF*-unkgM$5>SB4tTee(>O-R~SuuSCNOEiZ}nF1RrX7iPmdES;5) zc6FLFh@&G-rfY&f$sU?P5xzCdro%3{L3eQJx-`^?>Sc@crf2TJ+@AW%sf(kLO|5(+ z=Qk0HL*DOkfXz>N&U191lv3d=_J%maY%yZJ#2`xuuP{kB9Z z&RWjOOH&I91*SeX>ak1e1UQy~F%0X`lcSn1NZ8Z)G_l3!{)U3%89cI*_dvtT1Y-giP#`=qn9yl(3C1|vXPqI;#^9R=Qhl}H7#wZX^4#8 zh7@q32EYjQf)EW3wh*J#-7&=N0(K7tz`1uR3mg1;rMfaSqM1V8t>#)6XbpFZ6Gr_`Srp7Mmc4gT6)sx2+ zzKiqTaH+Tdoyewl1^ao0x!!T2fBpJI9*E4ijQ0 zz;)l@AZv`Ght93@B+%DWE}vNm&oi0o`Sv?3Qv&w;?gp$gA7bV@bd9avt;Qvn{h+m- zT9KK}+{ZU#j=LAPkrB5yYt3_yDVHqat;+fjGs5uwU!n`1h4LS9=)jG^A*?piY( z1VQFf@@__rd2#Mw>R8+2J{-$)G{WBIV>>%hyE7Kn#e3A{u#t&3gt5}@v&+Nf=nnBM zxdMUnn!!uyqs&(MeW*XEo9fRsaG-)Y9X!K)I!jvZbtg zG(PXPVnGQ|>?%8)>;^x=<~^X~fqrbhyezYMn)7}`)*62mz^)3)uCKX19)V)_@c=U0 z3#KN@9tA*hzWo1f$0eWVYuR#<&Nv$Y>H20&zzeQoTAf2dR3%S3kyPMjf}MvLH3E%n z3V;;&SwJ9bP%aI(miuMZ#Ql6en*RcS5{Wr}_oTLmY0A|7om_t+N8C3!d;}U!?x3dd zeR&Z~Z@h7XgoG-Iagi%6RfD3ikiUPvJ**^b_O?oa?Xy%o_d^eVrI6`q-pS`BMLnYH z`t#WfHqG)xM`D1~-&bZ=gAHO$z*Csh+v*srG>Zb<`VdKI^4KOkp1sL^)!BglgMinq zYg%KtYALA*2Hb(t_C9aN$lNV7=kf5F7ivjTZD>EzmKm^9fq3dqC~Fq3pdRp#8Sne) zs2GB6pN7{~?{{BZY!1Zxmno~c!0p_5;)!~L*7KT^L*g1|_nFd8c0bPY6;JrHDJ%fm z@Nrh6eIqf5PQt6d zYl$;spJEgf9k#gT!QT9g!<_@KGm*a^R?Vs2=YOTuB2rjA;3j-sAFFKP?zh*tVt>XI z0wQd7vP0az51iEc_njt8;xFX=2r5xD_Ea=F4=CnmmF0R2?52S!J+I{he%>8UEPein z7SW2tf+Y=*6NR1*Ww3DkvDQ=`23q7FDSu~1xEHFFRnE&znm_tsJx1GkyPFdI(oiFK z-{i>XbYY&9a{_XV|6#E=d!o;6EPc(6>k!7MT_>I(_nl?I6uP7xLW>(SF{`DCuqcDm)K|l=c{obkzrP>&c-b)O4=W+Q-;Fd3fynv$1%!(c+dOx4?-z2~(V?Q17@@Dqb(;3c2i&C|_x*c5chYv0~zEvw)Grz7f9CZHRT4`5e2 z#M|HYPQ@^SsqzE;ax;|9l{{{hn#wrx@2LIyp6!nk-7Y_y^7(czWHWb4Nq&3EoEbYC zHG5aNd;yWS;RHROI}WtJ=<6BqKv(;Yyd?a>_5e+4(tF}`ISMfF_ONCcIuu&xKbH-e z;H}EO$5azGP#m^uH-qjpm1cW;+zdO$cK40%N1|f0@WE~odgU5z>$zDB^8#~Od}`q+ z1Il-?m*Ie-Ouv+D2{t|6`%ncfBww{~Ff`Vf%IsCVcaM#Hh8o808JC+Ynd_bmplpu) z^88S3&I3eP+HWwsWBszq^|u!6y0Z-)@-Ub1EYzz4HO{8;r6H&-%^A<%#Mu~|o!xS$ z^U#KA<(?}19)1=27TYMqmeOLUM8_<^`{N>zZ$RUv2&7FHjT8U7vekz>6jRalBw)6Tx&IrFF~c7k9O@Yh<$+}4@;a>K3lsvU-}ekzn&Y?|vYuzg%rvSEAs( zrvUhgb3oVYx_@9)K7A`0p`T(~Am}3HTzuxIAzF$*sjWC!td*^k&7b_Pf2nPmQ0Ys$ zw=4RUc}B;)j+@4OJEFv?CqHaxuu7rS)mSB#_ft7_cE3oPE;9wiPwuUZkusIS>65$V zvwNVA#WKJke@kjk0u0zb-gY(h%Q(iO!#xiu*Do# zg3yLL+>WV93@j z&RTpe1-1V3+c?9&v%BGCNts}aQ0_Eg?kHSVDd)3M73b?WTY@`?+D=#7$42sF#2oL% zNFDYA*0=7Xus>ZHdQK!FW)AE<4p%!3Am5qK^YDVT1$XPCFK*LPH+9K(f3mLA?9882 za1!pf|=TAR79A20`Y+;uf*RXYx#3H!W1f1e)_h)^BK_^Ku)RA$-s3{5yrPfRW1pR{3 zYQLxPa&>u8C3`W7vy*dQIos!d9|_Vw`W5rqqMz`IEhdgq>QAx4_yyQ{C(!q9WAep8 z1-Y}Hw3}c3nhnW$&z}B)Z;5SGA}{g+QA{Af5D5TYl?_6}d3)xqoNpH3$)m-vgeRTP zUIDy|+nS(>RkYO_=i;96HX9pV-K>+m=QPNFyJ>`PNOP-3QoYX&6bzuDt^OH}FoWSX z=yCh@>hrdoAr~33&rpkBkMBUNBq*T>vi?#S06_!cet>RTAO_D0J6mc+*;Bo&l!Gh1 zauqgaNQPoEi7#+3mEpU#?3Do!PyCr_a!t)a8KrDS|73tWNJfAEvy?Zq7Ifq1^c>7U zwZ2A_d3=hprdd%Njdy;$e~w86*)-1mN_EEnp)e zA+~4w@@pXUhj?CZ*^yPoVzZjPNwrGD(E#|FAhZS?eDwHDR7%Ku0+Mg z^8X=T^4L{oF8KPY7HGVh3wJncM~37nG5fH} zr#kiKJl7B3*N@?h@UKgN5HbVN<@Fiz4buD1sgzm|$?w8r zbWHQU7CANl%{94pjeb9XQI&?CD`0;#%vaR7XKEtA1En0s;R*)1n;iQ283%6Svb6{P zmgn7ht}P_07|xb95TO6Q(58y3v{Y(pZ2Wm=XNM*xq^0GCX~dc%`Nxm%Glvscm$%E7 zjVT?I*N2S3-n{oFH~72iqkzuyo5X;l8~10eYPkMFjJhTGX+4*3o`*`u`#TQ0}WV9fOrSud{iert7B zMQg%XG=5)r+1+QbDy0EIOLj8?vXWeLitN($9Rk1Ky{+whgCzExzDty#Y6=9Nau--O zo;SMq`xn6_3e5bxoZBF&cr3Ci*DhcvO^~&{EWO!Cyvp?r1Vck_+qp9B@azfnn0{J^ zn-no7A&XhGGDSP@TlP!1zPh!-7odB^$aW(t{p#J{s#UV>3z#)Rnk<@f^MzK z!qpQG2kSp(#k|#@b$G5HH2keSGWV4na@yz7v;m~H2Qh7Oe<#+sqU`dc-jnJgp!>(9 z^mQ*hYVKyvGp^g7E5p)Iw-TB0Ug_7LP!vec%F(EP^!b|E6iiP)6xTgBFiCUyVquGu z-Rz}PuOI!k>b#}-!eJ?v`@V^alPzW_=HF;HaAtCK%PsFOCD`@LkqMG)2IGzhi{>D{ z)!g$oEV4hx#_O*M!Hg$;Vn`zQZewEi-TD@C$4flvVmznmy?*iNZn0H{_}U_nA(-nQ ziD1NRM0kG@bH4ESQckjMU5L?y!d1Vv_MNi@-mh(mSGsKrryU)TtHtBy*;DC(ZIS(1 z*ovBYv$@s0VfH(5CG6(H8nsAvj@I=Bno)LOIw=&OGvBqwV~UJP@h$jIrvo(R8QKZk z7(zD`ej$PLd-b0GH33@uTk=7u)Bb%g?XO9fMH7Ukyk*3?+*!u@q`Eh>%WoGnodHk? zw=RjYM&G7vgwXc+ZHzcSw~X|5n?3UQHO(k5+mN&dhDe}2^7fOmZEha$ede2tcqrmyXP zIxpARi%Lt`floxOPN#wv4<_RjTP6d;*5vhGaJN5k>$Ld?>Wj#mkmnnh3WihlzB69% ztYna>yzyz}$wvkip)JPiV3!+Gy2}qdO%kHwfa^RwQ14*B8mlC_G61IDYIBU;%X@mD z`fgmTZLgSTV^+wRp933Wh^-B&H;}D;PQgcR-CzeSI5&+rKAf+Tk{&3gy9_8=GuRYD zQv55Ds2mECtUhMybM-c;F%4`ZfQ^1Tv$QmOt#avvgs9c(_!67nm;;n&TZp3_V9my zyZw;opQq)No1x{Y0=3LN{js;K13;M{yIpQnvr0eyc-ee(FWWVdICbUac^c-I*U6m_ zWJV@GLgv0}7MBBaE@YN0N&C_SEbd|v%1CIh@bcv=ykX!>RpY=d zU8&M*$fg%gYThnm&jVit<+EKsU>|}2@qdMsOxi-Uyd#Z=E8F*ehF9>{%}i{Weo#h% z7O^(KQ{ZcHR%5+0^_HRmyq56bbJua-BAWMM00=S05Dt}ouw(ie{n+e_4VXw^j*Q8kwC^s|U_5S=N#MI=bkyWBvg5II4p4PHIbs5Ly~^$6Q0+M9NJL{PrHKdq!Y zeE;I%QxVR-Y7s#_K2F?>V4J`pxzO`W?s%?UTy23#(_#GqZvHR7Y&G8Q=^HN?d<6de zn15{xa^wE|<6GEu^^W#Gs#CMGo3KE`jE|sn82@La~fK-HZA7 zS6tdM^PsqI>%AELqm8==(*o(vBaAvt@^++{;6QxLM6ko*N3P`=FdNa zc#<$os4Xya4sNzfBiFAp4SbD2&wk9bRNt+(-U}z1$X~OT8rphl_$*d34$8Yq_3qts z{IAPhL0z}Au{gGA|0+FGJuzv*X{5x^A`8FY9zkId5uXSXg`a3Lxt%O$*RXUt90hlW z;-R*qsdMr)Vh`NUX2Syme4)@WNPBN>=9Eb+-u1PRTxn;Ky^lEDF|rRaE*Xs8kCgzC zSoLLj53^>Iv=TRneM+NLjQugkX3$mU#1n(qhq0myEDI-Mt~1D~PEB>39i*Yh=`$Qi zy_;0WXo0Db{8{P;2gtDCUgkGvo;GOFW{?-w>ZgYaAODOo3pz2ezCdl~Fi7lz zNHi*WXjbFddRjs{0aH{y&C|PwCEF<#%$g^|(!P#`4Lzi?wA2r)PXSl%Nw4WQ`d9?! z-f7rVdIbM$<7oXujd0-K(8L1#=v!#wq!UhRY`^|RhazZ6>`ee$a`$ORn|N6JeO&4q zsskN!{kNe^?)4x@Snc8|Vg9Z;ImsqZ(VvE@3r~tObOX-yaJ}_qf8x$>CYc*-FXeXL z`Gr8(4tFt+4_fLuxy}CTS^^kL_eY}BM!UrrOXcctyNd#b!Mh;joT>UmvCu(RFg2J(J z@@`k*x~xyewCnwweelN--fGlT=o`%fRk9E>kdh2~_sljb_1bQoWkhPdyZgXX6461+ z#{5#sODE*GK38{~_fuPGxLkdE(V3=m!oeznxktelLR~3*+HZhfZlRp-wl#QFcc3Vt zken7&^PNKWm5Z@28X6!p7tc%_z4YzcoXh*JsNZ+IWV9;C1cW|gc#T?p5D}a@6L8E* z5t+3`23f-Qp&x4>Ldvw=_Vb_@u}o_O7dhX3YNJu{tp|CXuhfs) zT=bJRr-4TO2lEQf#4mBb;}H+Vk9dlx?Qn;uxi_J;Su^gIU8}9%_6-{`*U9^uJ5-`PH)Xq&BKXT91daOH|QkC;r%^I}*{cJGGP?bKQb(KjE{u^Y;@PZLI@){$>^oz zrKa6Qn@Fd_@8}B-RhFV6a6)w=IRP=pnG%V6{v`n&KlV=6Fr5#TEUVb3ZRHuHIO-^; zyJRqacI$s{o3Y015>*SaSrp28ys>PgafhHafkk9@y{ge`X{|zr$fc|~)r-XI$rvb= z6hB;{A#M~5eSJoZiuSOiw5>p?REX4lsaUTSr@!lI0Bj^GxMbUyzDGIXQo04C@x09I zvn?2##@b!T)~a|0ojdqG9c^Z(A7&M{N`)`B@u|Bj3TMvbDorU?d8Q5_6D5z>kqHlW zRWQfb24zUs;*U|ZU|+wb0bGJgpcv|J{q_hP<@p}(<)yz3C+Yt=Fxc#Tr?&sT*@2q< zdYgxoce8=!`VyL$e!J|2y(4!W^?n70KzlwhDqT<5rmt++2l)2Xla^FqTN0aWc(FfT zD>Ko-eme2mTZF5j+8h^K7kqF#4OQ~FNvfrhQ2JJ>=l%3X8urL#DuTzZw)q@^TDzr~ zcAa`7vy&<cLNW-)Gu+fX^y;i7OQIsRUll=j27)-tw#J4P-q{w%5 zctK5FP~7>0aAe>Rhh@(*@)q_dsi1;nUvyIlvr}VI zg6whr-1o%ihPyDXGeE$@J>^7Re^1sc9kl^oa;1rVwwjcakaPwoS;uBv;}@;op8ZJy zLw)^xV~&&h92&6&m^8m^Bt}q2UsC;4KWO2*(>CM!(}jeP-&>D7RNPy=JL=8#@8D7} z*Y0BEd%rZ9;{H`zTORnQz^w}@*{Q+)7GsVCx1)^2xZ5ojKap z96(QBg_j>%q&e{sq`769?oEe(@#VXIe+u;83G9aQH(hl*qiC5OG7?ph%eJchb!;&o z7+0K|XttU2>93gkvmL=tU}(b`apvepX5ed;8*gR#`C1_G!r=I$wEN>>(=RvF1`YuM zWq&$9bYO6JuH3Ekzvx6$A<5Y(I#hk;SNF7ye@D|}g{N}mN|_91PTZ%AQ~WN`CN+#J zd&e{?>(=b;SDT`R(jH*8my81QU3Q1?QD8r65N@kdEB8UeH%??014xB7{<2orT&VsJ zm`wnn-j^j) z5%K-Y*UnJi_=`|&jC%e)H)nbWnt!3vquUaCXIi1i-EXF3wud{o?%Q*(3A)!L%-}@4 ze;rLTdK)-y@>lkkA?8V~4-n^7_9cR_RSfYZ(MBmR_-bnU2IDciB#Abj;!1^h2j}8oSy>(8ZhK2^&u3YQA`+_xmf_ z<@L2#Db2dqd%*8WkP8RxKL(-tDy`@s`=iMwF`w62f+Fbj0aX_5W#{zwW13OW{)J>L z0jDkYWF|M9@$1vwKakb^VljOD`L=v)$$6CShYIFLfCXlsJInfs7rvAQIa!j_y@I*g|=oh)wm;i3d`I$#<_-%sl?U@?02=)X8m z+owP4=*HviDmm>I+3Xe>hT_^H%gW}^Rw+M*7qwd0CpvfmnktcNA)T7w!M4(1B&-m3 zyW0m5kL)jP;TGgOKc7v>Cx5`k1=e%{`meMxV{TTIsibj|Gqg0;Wfk;)4+*11OCe}z z_+YYCG1ZBAyuY=ry>HC{oYx#$FtD-R7ajOKPw}gD|Fjo{7=QRx2?wI3Y$Z0tJH#HLS<<-ssH6w4z!i&KQ{V(M~4_pxhrXhiXZG^ z1S;yP)6k~lYV`W}<2>wq5INhW{5(;1fn%!B*wx;m#XSA$|09T4)L6NBZcI&;L_BaN z5)ykdTMU%o*%o5-D-@-a_*$<{=-%vIS0e9c2*aB zg`wnNaSqwLvcuJ2dbRpnHy20QgwlwDLw$fjzWCrmcmca)Jx{V-%i2n-3)JEl`haJ& zsw7XO|DHdws95n2Yk=_aX**r{6T8vjm7JTVMRJC@@HyWwVAbnXe{S-h?f=(w13>3IU{^!0Jyo*WF|D_?L7lReCceF$0Bl#% z24KR_Q%uT^VE?PnDF(jJMPL_Q%_kTPc-?OQa_H)?G6<#Mf!Vna>*Pwhw)!V~lq*9v z`^Q553_Sx$E&&(zBQ?eF1jraFq(w$^+VDhVGB-1f%%`ko-B*t}+PIn75ec}pK# z$RYONuD=4522^B8HYgQ=JggNzD=UR2tQG7%CW|c=b#tbF?x2J~mq03*fkMQkUP1n` zm6(qGqD|3l@#W#^K9&v?&KSYb;^+h1Tw#bsAx=-{?^v*55v7TU80QTaD;AMapZyI) zjEzy|Yy-o)kn8bT<(P*>-wct+cmDnqt@_E}dDPE6uq`y&wKE)@^JM+vUw4knb-~Pz zt@+?K!&)mZEM`?A8hm6}WLPNQF4Ec!1!E)AE4RX#k)KM9k!i;Vp-X&@l}ohVz&e?PzftknH>W^z;j!gD(H!Mrhka-FLzX(GF&$- z0wTPMK?QJg(TsAMgpy%Oj3b?eu-BRc7r@R(jm_*el=lS{@dlB+38}y4+h23$FVq3T zYl|apf;8PC_oMOEc?RipQPN^8Cx`9nxNu+O)vw3YeEVYplo{ zP8Qf?_s6@JQVaCs9m$ETo&>1j1{!rpH~2d}_ucDr1$b89&92vJGXJ*)*V${5?|9@W ze9nV;Oanw{*K_>2b>*Aih71WJ5k$sK@1%c%2d!ux62FP9b%b5uF_`)JCb@0=>RtD? zz!bXPjYdyHj_ilbi0F5;x;dC+Fzm$7oJ9OSX}JqB3hXNrIjXuLIF z&><|@WoXo1JX1XJ=0o(hQL|G5`)1unJ%V;E3Afzv zP=6C8b`sqG?K-qmJX8AxL@YG*o&SAqVD~Qr-#e^3A%0{_BHlfg9{47*=XV!N0&D0O z8+_1U#k_&}@@`fDFD{A6unW8sLG((-*o#h(>*r>)ez-x?daIu%Xu}L2K?f6UMSn2t z;jM21DgRJ37WFid`$RfF92pszy(iH>pKz$ZB)PCt){BcoUJ>(4BzCOzmuwb5f^ElE z*e8(=WXj;O+3CaX_i$bu^!`>ty0yzdjh5 zz<0!UV_eOnO)uBclju=6#bLX8Tk&D@eVg<|$E%Q@Tv4*k32z+`aa~fddLv9})=DU{ ziAo5W&}RrtiL-)tfvk-2TSK&X|~*v13)cG z-i`W7_my<6q}m>Eswh!Lx^`ti+yFPnw}?0B5|t%(S)-N+{>_3cfnji@#Sqr2%&Yz& zsa|LW$N@h+T~Ef)z9~tU&anblF*xiNiM@ibzn*+}wpR75iz*4)U|ir!hjs(z z_|M#2z(hLxN|Oy%C@cz}gGhbT9JAGzb_K+@6Rk#HBcW)Nu3)kI+7%fUXEcD)GO|Jv&Yph%yTR*Vj$ z)f!Fh?Z#4ezonKy6Q`r}7; zzSzarGn~?vbkg?d%EP&8HRMCie4Ea~G98NzrbnvX&)%%#9qSYEf@6=oqAJP|0tO>h zXVBeu5UHF{of(20ru8dt0Qga|8)@uy#Wv;zcI4K_wxE;=1FG3VmD z*c9WIjt9yK=?dkj$G7FNEuUnSks=ZljJG0E7!0nV=2968@1in~w6=&w2{6-=D_UFb z!08^a81Xg8gAIvt!d`G>fUkK`uh1t!dZH0R!Ja5k0^HwNF_M>a-ncg>;~o5YUI2)w zx`IwM+tZ4(2%q_i=D(?C#K4yMM1C7*|1n)nKZ$vaj-e9CCt56>b^WEp!R?b`mBn37 zw!MIDzG&l!YPRxmT^RM8&t>(xAP0d3z;%(NQS0pw5;+sk$L?8TQ&u5sYWf8RCLI43 zHo}NM3!^`>aOs4$0oSxeFE;2gN$4YB1_H53(8b(E;B9n{I7yW|f3${bis{3Dlw#G1 z&AZg0VrXe;;|SOfsxF=ZomnA4{Rx!msP(1`T$;?n-?a)8D4$Xrb69`0i~h(?ji%-K zH9egiME)ja^?6z~E%nM5wMM6ZRiRCSE4q)lfwg|sP_x!xkjajN5zAjLBq9O=sC#EJ zVBj@Pu?KCJdRBOOiW-TI7yqHmYLSuxPg&vE`?1@?-$7vk9gM%{zqrn!)j3QG+si$C zwHW!V`r;w70?WtN(%_31CjDgAU{w#YCjb4)f+tOe)(A|rC`0LE1)Z5Z)~?kL-xgc^ zhOFD&cZwicTkhmezn|HW_vUT4sv(eJC8mH*|9B-P%{01^T1ZGp-)BFC!*(A2duuDt z{rQI9&>e7h7trYz(Q+4)L=fv?0=V?QbRifK1Lkn zu`G7XJP0FzU>InwNxV8Kekn`@Rq!}r*IMfi@PlnaJe3CUT-IDx#K6 z>*}Znp|rF9whKk*cx@kw7W`mJS7^}d3O||`6V5j~tj$dTxzb z_A)!HYvy3c*3o{FJRmh62jaXW??SkPC8*|}kC`O!{~oV04KH5Ltzv1{qi=%Q99s)e zdig-(vDQnmmVSYzGqprAqzman;(o>kby;mjd_Bb2g=pk=P^|4i4bw15vy9O_miGO# z`J5^>zY8>f$*lJDG#)JZbNt;V6ORpsvc{nl{TCC&gp>qV*nXFKf78m#!+vO;Zm^Kc zD`HOH9Zu+NGk5#Q9m{ZR<)RzW3!e0kzfKhw7ZpwS1O@r~`^S``5U_>mG+HKQWE|IT zNl2=Eu!nY!D{F;f1@WWp*P{981A)%=R=Pg;X!-N0S9Y#AEw(|IH(TSsJKEq`w)IM3 zLNhoiCbnPn)`-^)xhpskHW7`fN;JM0>UsT`t`VA&_?8k<$gh31#Kh(RVJSxB zZt*RbM?jh~tTjrbx2w9r|M9x<*ui5cj-c~uhzLU9G($fybH$vC#k=nPc(b;o2cSgQz&UL^MStDmpH%)D3R6vIdUET-I08bNbqXJR3qj zNzs`jo%TZ|>}<%M?|*>~9FD*A868d*yQKfvYr*fNo6{S<*!pRj`Y`>HAC%+8Iu~=H z?UcsT)dX$@z3MQoZFE}L{d-cyPh+s_j3AO{^#fh|7cQ+eI}FbKJE5alYdHCXT>P72 zO-|3PY`UW%icK8<4QuUlZ~I9iy5PJv283ZdrJh zlaGM0kD`#*1qdxX^^V%Hp?Ti$1}TcEj1Bxk6+mz3&va`H3_no4Xi=I+MxgpgdDK2) zhg2eU4t(S){kCME8`;2pcQlIHim&3|ma6sA$i*YnOI|?}^hdBcz7@93#Ym3hlZm-C zO5e!CoZ0Z>p~J&4urW2~6fi#Ug#@N~Ob~mLy`%~bQ|jM~a7`dX7&>UYZSy}pWKPOw z@zl?vVEqTPC}>Wuk|1XaO#VpN(HG?SQ2v8ll~ImDchr5L0NC$x3P#=y(4#zo$C+PxCIcNthtFxz-s;Hi$}eU?&@d`}tyJ$r`x? z!AH#eRY<7&qs;-@)R)(1+Bpsdi}8|pa|;X14{V@+kLvd%ZcGfK%v$bPf`cA>Y!oG1 z1!_!z_i_a~P>c$ydEOAuE+`r=Gq!lEJ66XbFtKPr2cFzku`S?VlF7r*|6x>)Eps&i zRui~#SMJQr>>p>tKB%_#E3J^3ld|^uVkpfY@EKEJ&Zp?&QUlwMJX$}FlK$hAy)E3o zJavF~xy6b5=xF$Gu~4aP{P52An3~fZP(y-^i)+ed)E0I8-&}x9fEm(@z)$aSJW6xlH%!U+6Sl>8?Umn^95H^qI1quk&!>dTn)&u&weFtp%3`@FH zn}E|DZc$Z>LJPi^Ez6y9ver{k5z57tq?f6fnR2k6Wt31!70wLc>z%5YMGq~19K*=} zLW3AG>*aOuR*&@QlPS!ezyl~eo7e3i({1X!>-jnm6l*okjP=_OpJ8E;Wa2f6;7%!K2It4o2 zt0zT)qx?RbE0<*DSiIvS1-esCe(;X7@0{t^<=m48pu=?DxAXoMcU3BfFMJa9WC%>k zYlAH-iRj8<1L)5DCi}=czl`3NXwBVP^u}67JtU38UDpxvO z5H^ba8*_yQ{{EBj4Y8kx6jW@m3dwB5JY zT`d_JLrP5@)TmUa6CN&7Ff=rT!U_J~F@qw=MGP(;qFE%i`9o~PAPZFMhKQ-2B&mK= zSpsbCyqLk|Z090MT=Y^Y&SY!HbT(pdwSrG(eS$Vedbj5Qtu?#+&wAW$Fpj$+AKY0I zqc{n7zcYWFTqSX$!qDa)e!9?2%Xr9)Q z4y-f%ML)|~m)*~r@r&>v4dG+PmLdRka!>3yCaiIckqOpMDXcU+0A#UJG$2+=$LHM^ z726}m!}%_{AX^fO*I+hrOKau_6?fVxcvA#uUfSrCzMqWt|^YIvWXo=IsSBv`{(kwV)X z(iRtuxVR>E8oH>k!rBm{D#>0#A02dwwxxE*lO_rai4XSnlFqf(P*JYKr1qb#-QF7> zTbuBDSEM_|xI053klq=Uvd3m>Uh-sOOs=<~*t$95;mSF4V>k!H%@;79mSKES=@Zjk z+_Rz?#5qT9o=Cs8Llx&*XKy(Gbl6uK1Soe@K&|8}yDw;<2b?Mfl ziO&Mznf8271U7V<`l)C-Zpn9`lcUO886D8T{5FyC^4MYS#Zkrq6%vxrdMDZawZWHy zz&qD3DyT3CgT2Z0N2>oQe=w;(3}vGg<%UAKvr$fN3~4MLGVA^R;=}dT^os{<(K=Y$ zj_5FL=nJas;l`1VLCbjKEMgTjiO~64BAR3+uevJm>x^K!XainliBPkVX|Pg%8VGz{ z+D44IM5%ldYbJ+tCtt(ySb)_pyEo9^63DlIoA#+3SuYpGbjqxwc2s3Nc@TXJ} zkViIB2jhz;LOz^s38`F(cN#H|yYI|>8DnR)GxfRS%x2Dkjh0zmU$eisA&5srvbS@h zdcYMA6E|Zr=;B&b!)x=b3@TMaAFcqn)o5GFp$}U6W)7->EmZorzfiWbxHAlKMBst` zfM&_gQy@%;D^G6tXOhO7@>l)49?NLytI5)MOE15o0L&?mw zZ?2RZhVKe}vXXDFj~CK3Gxv|&bLa*y&(AQUQzLYDOB|~ba?Eb%$1GjbJ>S{KRkd-L^A zVzTE$>PSmM<38nTW*rHRGG6Q3STr}AxO4;$OY(Qy;a3*YD z%IXc}U2$v@N9%Ox1~>YdmWEMyp3vswgE!%mEn7*ESe@r0rZs_-3%RlT#>9fA16#4% z`?}NxI4J~$0gLl@r{6zX;NcceKHXoX_753KkN^SIZE;Y$N5oC&@nS_CSd9NSgk6dn z5t%wN$<-lpTfJNb^9wkrR6oisTX#sf z_BaSt?a25)J2KtR2@IpaiU^Ls<~3@kyf3Gx5<$y>$kUS|x)3 zCy-7X-rr6T8J*S27X?^yfHl5w?_`KnbnhKh*UYsJM0BpUp&%SOi3vwizMeq36ocHZ zGvW$++#kOMLeW~M8#62 z*o@Po*0hPAXi}5a0NLdZPfXdnxzbnAHkZiiMHhY-=+2i7rMMbAmkQ3<@)UZz!x;UI zq6s*GS$HuY_QmdY%VKJRX@{OwK~P=>1?Io~t&kfLZAZ-G{@<2u#oJSDMFfq33ebrO z3Oe0Tm60dn^lfl*4Zfk0B#b>;)rj2mbr#q>ut({yF zRo9}0<6OqTXdBT84UYkZXaWhZ{F_iuPDpu!Ts1}-{53A3qFr0m*DD7(j~vIOX2wT9 zzGhf6Zy_JY?*q~JYJfF;4`YSVX@Nw4X<2Jx$mN5hv0DJjfPxIV$>BBClGWvS=~q^N zOLy7l)iB*j)ai4fi1vz!W$ z?$yjY4sdMFMWM$rgXWPpctjoz*rPt^R zx*O+iEDa>^EaoShY&UjIl+@u$Ue*ZxoN3X=4?P|{)bI$0upXY*$S7e<(<6CPsgL+H&hZqCtofLE*0vUhhJR3iMjn9MOem?BGK_u~mNxvFdMEd%9rX`E_N z-3>t=w;3;H$U{%C;r>cLHjKA64$5s|YX|f7h&*~{QQlIBc73rHh#_u5b6|~ARSXqZ z$#;*tyu~Lvt>)R_pDT-#p66RYPc7_8NC+bB%{C3W5K>0Cz zz@rc?Zl9?onq%jV*zbl#HBDWCfdT0t4M<37matm$6j+Be39rp(_cOMNUbBE6ZG_+t zdO%tuqO{0vGrYrBv7~Qp8PV1C^Kjffx1p66u7VGrZ0lFc{?;$m{9PY-@>$}Xk0Y@{ zHmGbO3D`VQhMs9eDWXwha(QH8Rm|j@mrYs`n+u)(`g}RtTms5Ii26^N zhfc@_sQuyiZ()xHM+h-Z@F-A%2jUgoRjIFYY{B1pg|ddS3UIV0`#WJuJ|*CLDyhOl zPOy_-Q9)tMH*?y?6Om!qO;)3((%e@x-TCCQ=i5dm@>)x691jIB5wfz0bH&=_xkOzq`rEKKxtfxBi!TIM?2u_+Eagi;5v)?ij?^2} z3M@i%x+Y&O)$1GMUbrV#-6k^NX*vJC1Z1{CsGwZTT3n-~^j8V`Hn0)~wqUmJbkRJr zvbFirhSMZ$*dMdE>XZ9kcFXKa8ltO>5NuGFKH3NwK4VN~wc$>@>CVkAc@2|fPFHEW z8SV+xdIYx!O8qpC-00U0Au5ly5N?Xy6juM>WEr{4L80Pti#U4>r?axq+_c(zyZT;r zo(ow&6ui~rxi7BiEmH=~RI=9+pPJ+OB;$Q_kMZRSq5JG`aVzDQSsgU3iP|^IvVApl z!?_@y)yActUJFeX^Y2ZhVrpF~Cm>(D+Tm8PrE%oo29mVDWac7KGz1Y%jjxasjJjLH~M4LDA{GCK{_#i6YvB5awy()+sR43h>Y;`}&! zJc@WO*N=ic@86%_I@;ZNAN_SI`?Do8K0k1J8Uktn!3P6iYW88d0ufz2?yB25k(>Cb zJw2n4g*S!OLGQ}X5v5a^HXv`te*;Ck+hK>fQqC(`S_J|iZ?%a?>A!d?d|a7LB6?Mr zoHa+|d!FnXWCpuRWDbPSTiR>wA9N#i7X#S?Ja3nB-MTaAqv4V{aQVU8VeR({R)Kj21u=skyauy!qHWqQA)sv;acX%kZ z6_eF(eMpP7sZPT2w_h(cH8^;+KGKd&=pPD*wOG>OO0939VM|;VTmb&`a6@}j!toaN zE*kcX~9z z?us{t*Vbbq^7rT85#jF3k~AgxuUb#naAI$Dw-292NaU|sl{Yj!z6;PLh=r;=7iyB4 ztW}DbOcqZsgx(TyHPl76DLJ>;Es@_#9&Bxrb^zrg*~jPSRLw(X)_l~8%A(P}KU~=x z9~N4&_1}#1*WCN#P2AQ$y6YWit+IK$+g2N$*`XH9^}02>?{LW~Dj=%A_~Vtt;uEiV zyL4uz0^K4-2$KW`@FcCGFj?KHJ^@K3cu8egc+pgn+OqJ_{H_YJzw#Ji4W<0#T!Qg^ zaa2sxci{axU63^T5Xxb0xXUBfTL&B)YT8y?`bP? zLy5$#bb698o6b?!RejEhN!_8ExXkQPiJ5~Ll_iBKLQiRP8Mus0fJF<&+r2Tb<(0PhUTigo38mz zeYjZ($augqGqtYPL`oL)&CP`+B<_$x#qi;OWm6SNOHB&2qJaA66Dnj*fKB`5vHgto zvk8IC*M@+FA(aEqwR5~bcFM^wd48caGv9_JKlqEh{eFi`-Se9KG>j6N(;lWc$129` zZ*(9mbP)aERY#MpPA>O$exc5l)n*Cj$gCZdrHixvd@8-6hedS2yzIjmuP#pg@=;L@ zf?UrkU+s@zl9DDV$5#9;EFs#W44$%CimnpGS5;Oe1Xic{Wi*}xFbimaS%mPNxn4;2 zxDc#L6nmeTMrTYXGp2}(De_sz_*Stv`BpJ9YfasS0qgl`${F_uNC7REu4J;zOzsZI z9^ZU^P()s9_bElrr}lmYDW=s~z@;emE_blZJYI>WoK4$3+6F)51P#QRd#UW;LJ-zX z1kd`~|In4f5o;xmwNEF%hBnnbp#Rw1iq=*fp?8%p%Gbc9E36a828Ntejm@6pJUaW>qZ}Bu&*}Zi z5tE$nh^G5wd(5fM(sNkm!s6}oj)CWtJ0lPow8;=Ys{N@%SCW@%N|ADhqwmgqL9PB1 zxWx#HtGqe?9c#;M*Zw<0s;H=l-u%w!2SENT^zFLcH$HwA?J3iy2=wd&*<_@fvBS*% z<|C&sUw>Cn|l$tvPe z0ivVEbfB(^yi~gIG(Ck8AR{LuyEW2LoAO=B zG~aCQ&!XrfMi@W=q@^LJbFVormt0Bi0TlOx6V9Vy7oYF=!?Og7&M5Kw2fb^D+xfr$ zBqhNE7GeGHLME^_ra~rY5nddyb|-StO?YZSePE!s7>-x!M7HBtqg|7zz|5mziFk9B zP?CcN^oWezO}@~*Pe9ooNDIw{-dKLlD-moro*En}c@mOi_kIYqP3O(qFN^lgquG7k zw9iW?F5eSbXG*z9k;tR{$e=jan9k12hDZ4Na4Ej|?J?+YeJq-)w;OqG*Lj&rgEu_F zSAnm%n)MXXEQE=@ffV}_wm&WXmvozKeeJJMFFQ9Gk#Bp_zwgLc*(Kdq16}e(qnN!~ ze27hTaD`fhF-uIM{#G2$)*j30+=rAtGN!#Ql@$6i24{aMmtIjc?CC*cJYLqxDX{tC zgDFH}_vqtKY6jdMK}3_TBkBwwMR`R;OmkD(?m8zp$8^;F#rxhU)DK?oRn}8RJ{^Zsw#!^Q@X-=@s5~PBd`9kHnyUrB(hd4 z`C4H)_<%YK<(>L)6Tv#ts6+uM^J%?&}%Tfmf$;(bk2tg`J3pEn>+{Ipj4e{3EjZ zI6)SMEY)80k)yT@@#+VXokwfG3dm9ggp`cy+f&^L_N_B*3UbKY0xdU~-xV4_%3+m8 zLm@wpZ;qd20-KzK$Ij3&gvZEh)%K8%VBhn@x{dLbT4LNQs`no6;2wPYu&CkX*AgBa z1=SdAc`rqk3PeyilW{nEmnOqsFbh_3hzp35y-987%Q_ibWG)GYe+SxhYb-eaVBt|N zm8V9>QT|2g8s$B}Qva#IvGntR4Gnxfmu{2!ZcBuV(ze{Ke>yc{lSyenQ2qxL*KZ32 z?g|5Pk$q%7>wu0JxbC$ye~e;!r%I`=w>Y0wDz}Ix@jGc!oSy(J392tfZRMh=-g_}XTCda_=V#f3y&zo;@`T3hCWs# zRd(28cncq8+ot?>M(RIYtigP?gYVQG4LZk*UpL~gB6qu@mulm3<9D!xElDpc@e6cDuhszOLm!|^Rm(|LN4PlQi_#wq4pV*$2j!)3{Ju^S4i)_sA@(= z>hwE`B%f#WG#EH#+C!jCRDh~s`Bo{S#f<;wNNc)0*3O&0n)T+yT%b&1M^i{bdVA;Q z15<=c=AKIe-Sk!KpYr_-5KZz?u!PJqvf?jezRTSR#6BnD`^5GYjr?b8{tzOjvk*~XXjBmK+>^}@3OlUk;9kz`%|B&ZB;}mxtX5$Vv ztc&$H^?g`Rey4bB(mXlD&M%=NoH$|&ul1qiUNlL8V_DwEs?J@^8)Xm)AaHGa1|Fq| z&zrNDP!f0hS0?#|3)-Lb@<6y5?k~D0f!uGaE+E~uE)9{|^5UPwdBFasme$- z6y0pwf2>n9!ylz-`ztlY!8(;pf6vHQcbiUq3~?yYivBuU&Pf!6aH1@=i(AWPj@mMY zE#XfB@#Z1?x{;%>p87D^M5&Qtk84=?xOINC*3a{Gx3xc+u{kfPnwbs1%=k*LM4NHj zWQwrB#o>ICJZ4VRo(5Q^hcxRh1O0Mw30Bh&=*^`aTt31J1qAxYCPpntfj9Loiwp-% zgm!aC#U;esCgUn{p&o}-D0bByL+d1P<>^=KA>@dZC}N{T6s=6?8CIOtfz_i^p+>Z# zUS(eQw4x`dRx*jwgxV{Cf7dI3lo;fl6MyGZtM6}r{wBTpyE4W(%k-U!t86XpZ}KF* za6L^OLRZ-&N+U00d>Jg0EI!dh(!f&LiDcP#{_L~OA7k=g)K(s?m-5($sh)WYPBi44 z-I1Yc>{{=K>^PIQJHJIxk+IQY>rCk_Z_1Wy1fVCNQz$c@o=UbEPK-yO!R;Xw-muFr z-?6l}HtQ~>-4#KYEh=_@Ef%QA@7Y3GsKq8kRo(c|D0D0bBx{Z%KZj@oGvWAs$axh@ zY-G$iYc!OYo_VOm6yaMx7h0(hyJ!>W-sks8+PXG9kjNv!A@50}S6e0!8xR<8C6keS z%~t<6ql66+{HjWOZkz#3cntOVsz$67d6M&umTzr}-k1a>42!)W_j zzNawtf3*NIzEOfBHhH%YebUqc%EIY^<}bHB&XtnVgEfvnqPr234#hv-bK(>+_&YIe zY!UP8GlSJG6swd`8WWc3TqPBQS;$>QZ{+9OYCUK=<}cieok1&&*1W8* zOhISWEckN-%C|!e;<^&D)v=j&H20(L<>lp!P@?_5)XrlXSSgZ1;T3VK>GwduYy4C# zT^og0Nf|jey`qgT?Ngg}@+68FrrIRP9o`)K&JX95eMQ=ax-k}3tE?w)s`FOK+!f}S zZ2}VmK1~m5FEGM9bsY1k5{fp+>m%cdkuAozJU>zOv9BOma}1yVl@h$f{tj|~usqp1 zaf{4%>?6_k0sZ0epk_?j%-ue(fw#z#{W+k#{K@5q<70cL55A)y-`$D-fPta)`ufwU zW&g%@6%z`p!&58wc)xp!s5)chu7Ms~qa}Rq8^?#C4}hkAe0s%9g?zkI(V9SHLF1gI3IK9QKQQUPB!Y%GicF!Xws^ful+;P z_iA2CS;yPZBN{9QgYn_ggtJkf8O-T&+Yogk%b>Gli@ndjm;6{yEPE~tB80JrGK!Jt zQ6iDCf?7-lOcbjtK2a;KG5aZH1FsK*j!ZR20a;!Njve2|huLac8L&r(@DWz71Zyjp z4I@kQl<20$FcGL$d`RZ9 zRDUWgdd!A>yF8oaw@+=^<8>R?njL>IHt-k^0F1oEj*gkGwcE4$;auw?Oh?2cjNE>j z$|+Zi8js|wo=!z-^hJWEy*#<4$(?(lhSJ9wX0SNsy4QqM>nLpkJiPlcS9vBKH0Xvi z1+17?7dh#lcE!@l#K^U^!yN-ylON{L#|O4^hXJ$^q;~%W0tqr>K$!r(zlzK)9idvN zuRyrJ{qDZ;c6~U%l}0 zt8OAPw|SssyJFD>F%pI^ZZL!D7~{yg&PWl{>gThl#{KJ7{Fhx9Op%4c)1TNh?XFIXqbow5aIsZ^f%Wvyyat?e+|6Huu& z8Jb*La81j$LxT>rs!T8OEHJV+_CW^l{;*~Ly3Sd-GgR(2+8mFlv7O`L!p2G zSvKnTZs`%zkGkY~#yNQh9ZQjecP`uJp2@|e1@wD7wRff>-zti=>iJ4b$8e}{;P7^? z8SfkVGxY}b+lgl?6)G~c<@m3k?Q%;h6iylq;X8ko80&+$h57jzicXL0kxYgZoJtJ% z&kt=%_On(UcrEwPTid^Xu=-_uOC4?a-etO2Orh<#lIA{XMl#SCEYB-Tt)+$gqlWYj zcdp%Fj9XquCdFIY5M7i%?Jc-oycq6j4OjI5@Jjm0tI?3!daF^!e700wUi5@q=;*1A zSSpn*1xB}4q&$-)O z6%p)1m1vhKr+z38K)4`LG@NSKCwb&+##Bm}UhA|V1ADP0SmmO9!gjJi`uNMgB+)u! z1xdb2;AiBU*dt7A}E+Qc@>k{=1%Pm+VcT?@!7WVCMUvbYEN+S6`piYoyT_C z2RY0I9-Vh%Xr*RH`mxT5n2CwWlTS$Tszb+2Z{u~QIFnz0AsV|6cLCVUz+*rTI{H^^ zkrOD~AM+`InfQJVGK9&Gu$8eHe9{Fug2aFd zC)1N5N{C>FCs9-M*hQAO1kA-wl$M$`n)T=CkNIY>xt-AAHlsG4eCpT-(*X2T!2ETD zT4DbFfQE`J93b&>^CBx8&L(9MB)GjnEXF054VlYZ^WRS(X}Q0M_NM7@u&JgEB`Gm* z(J%%2`%pqITa~KhFK-k}RIXYP9umR{g-SIz*B3W9D5T@lMv04y+ZJ(4Ru1k&!IS=| zP);A?tb*`+!BOJKVx~Cp_@X!{(m4$cg^|YkSSoC z&q(*IS;wd>FU!7Ret1v$&5mE?2izN2`)k~u*u1oxHAIFAaXol1m@6#9{$;bC#eeNu zR4xc)zW7#QmCX`7Ch3BZRo+`r8fW}YgnZXJq zeIzVgWl48cY5W|1IT*+^H1RtIGRrr=1w4i#OO*B z>QA)=QnK}Ge;=V}U1M#o;z)F+7W=aw1p&mr*_P8l0Fa$`;Z_t$yrHChEp&kw@ANvN zhpL>{`zn7;HBq0*OmFRY2QDO#+yOWWt3>7U-x5* zWsiVB){M~Ljkk+vF&^8E?4e%E+TCO!;55&sGVfyxoJh5#~4N185U~Ya5&Y z&iZu)28rq=5)nBTm*=ZwD6kQukmV{=;O3{-?25AX&hL}bl2%gA`rB*TDUMpFrLVp0Y2EXY9O`B-eUKQN7i!9!$ke1EQVc=N&lC7{b`yaMxNmYn-h@b5QMi zA`SE42#|dB2+?keJ9?a5pu?>YF`cvZUrLi5j{E~nEq$-PJY~j)ls++#3lIb!Ffx(T zbZVRqW7_V=M(I#2Zpn^^p{O(Bx({qer9|h>q*g+?QU0w0IRQ7dmVAKfa-74s4?21RjX9Ew;UrHvC zE&f+w10e~dtaBrqAfGJ?Dj9=NUDy66^T#L45c{9*a62ch20oe0|D(?mch&|n*d{A6 z1LECDYK7gM0Rq3gF9pX#0uA-uuNCfr`St(5MzFqe`EPN=_(Fzns*{{>%DI$MWXvx$ z1IxwMF~d_;e0VM%NJ&3b1A|+||LFl!UFI98!y`$)V<$1O*siN>68vM5EXJE ztLuBp?Eb?ArpWFwLgGdFnH?qY$p7t)eE>8NL+z;`bHM^?RR2bnjT#7OQaJ;z(Kpnr zPiXufAca&1)eNMR$9JQXP=s_+w;EpD5{&<<%Kt9m;=gmGEaTFSpv3Ou{!cg*e-cPpQ7!cE!$fMp{r~Y` zKfW6f_}>A!Ousk7pF`Yoj%CG>eg6HLo10(q^8fw=V82~@`NYMMEY6mDgX@(*q-v0V zHP3!{0PQI88vuVsasB0wI65^*l!=WK&I!#AAp(%v0kPY|^+bJQX~)DpRGZ0f?j=GD zrvA6yiR^o9iY7>9!;sDVb_vK}Ni*$;xAFeTGXV+L8sVkwrLH5cxvxK|tcL_o8!aNU@<%l0= zz5Ta<^~})KoIVFeQ!t?HzU+bw+iob>E30ScWbnDGU3WPcR?!#CGJg7F*gJ_Q}L$SVD^k{=taor3xZ|rHB_-wxa|A zRu$kqS?o`18r|qai}>{1Q2b2E+8^=&0FIR0V2|J9+kgw1W9*-Is?}#)Pn$6XhM(DI z)u=`Pga7tDn}~8f)B9OL9BF>>2ZT&K1AX0|Nc<-%ec930Gd;v>Hqn3?u~+56Eiu*O@04cqj( zAcCqK`p>H`$e!<4SQIC9(#OFI9=`ZuSlt+}fZ*n%0qOOl)-ZwfAm3N#e!R+cBx%Up z=6n274e;QYGnrbiKeQaMyG}8@uLT`&n7#1aDLgfkh5dm&FNNtS5_deqos97)Xz_9K zdvbZ~HQr2tGAP!uvyO*3c&|3oD$zPp_(*ohwl&Xb@pLs0aFM!cHlw@(PA)GOjW{{f{Gi2B=e62_HB(8?#K`kEMUT+NrpGm zYY>o?WvVp<3X?_#HlB&4&~=1dE6TmaJ`$0V#2f5Ic1+<|i}@b>fJ(+86~2^gp(CJ3 zHfyZzYi&s0qHIP&nn$LEBF|BIVtO}%<_>VeSKmF0lkjTWQEPj}Hjg5#17o1M{F~U# zh4VY}`ipLqZDjHpoKbQsyYC=)uZFk3)7JN>V1_&Od7vQ?DF;_rG>#rK3caCNJYKHi z4uda=J88Xp=om-aUXIw_=~j&-@+*GVBH{Ez-=?5!I2IzH)BrSo8sb{(brLfZm|Gqz zy53;R-J%mdR5`myzq2`Ab{l;P_gUrP{jW9!2btE^%g>z}_CXjySN{mQn)o8xDIGj< zM>JBWGE?=(1$3W}#RQ9nH-tiF2g7f$CsL8SD^;9QvkKCs-yj*2{VNFzuk2oL2PT`k z@BTUGDS}}=Qu!?nZVdpu=o7@>lmPBqxK=^Fz9$V3^P|}y!(e4=H|6b+6-IKTL;{77 z6m|6%D4*|?`4LU5z(sFoJfKyKBgKFCO@-(5K-?2G2W`)p%61IjB8Tu|1=k*;W`9g+ z#6g-oX`r8opmlz0qv|>>vLymEoh>bdXOd!@Lma^rJ(p^6%7ZR3 zu8#WA=BGF|d|^ld#ktw#^{YlBDjn#FSdWu|P#i4=&^i>C(H19?25U+}^65)5mt)QR zvElg(*x~nv$&8^kms`_W-?=^u*WX$cC}SPdSvS}HdwtVaw+pg%o0qKinWhrOag^fQW#Quwg4tIsZVE6P7c{5i3=!5%|VNUC$VYL17w1mWh?$76u}x(&+DOoI|;$2Pc3 zlvYYOSEy8JC#oeGq5o~1z;}d#5Lz%DJY032+l7CCcB%}x15*6@LstvF(wS(X^(Y3B zF;qArBBaBxwE-Ac6V%E4o$^A^Tmz2QXeE`W47x1fbazkY%D&bgc?{|WZ`FNq$ac5YUF$e(#YF4jLB#sK> z`+#7*-H>jIEaw1>%M|X6E#;TO+U(PQrE?vB~)J&5L)`t*E{$oxC2 zFNfFb&j8F)HrEphkjK3Cg@BoyOs7C$B+~np=!HR&F|~DcI(R7&Kl^P@ZgrJ2kr)fj zv=1BA=$12~6dD|Jl{N9sH2@9B4Mlc6D-Z)bO%pddpKUMv-CJiF&{vrk-)eU*(`sV? zxbi?iL5=Zvyv;K@YAG9O@s9aoJv*|!v3QIDxAfX+Fjet`a-yIkuGX0lz84^c$})=!S!_52 zE?J0elpl_!O_GUL?Qh`yXbf~d6*tYn_F->ALeP)4+R6^a_Re%9?^9|@`Vo{UInt^J zLIh_4wwA9j&(`CJ)=|^Xp20`4Y%dU{V3*l!j-AOH(PP-xE&&eKe8ZPin?ug%f^@y* z-$x5(nBWo2TU>d7sIutR#yR88b7uQT1rUG0_I?;Sn2g~~M#aZ@Z7@_e?BM7t$?R=r zUsm$k`K>BpL{)L>GoR0ur-Q2?q9@4Io$Ux_c4UuML1WDBpP-0k1v{51Z&Sz~m7v7Y zx|U>>V0zy%M_XymgdensvDIfU0d1XN8-;-wZLBjX=FGRCQqTGkCqk*b-k9{0=zJjLp zM2t`Qmzrx7o2Do`nF@G6i=#|r7T6!CbGw9R8yfG_2FsOA-6lBW9!;B+E^+;t^(Hse zokfwoW~Csl-974& zU{{Zy3yvtv%%uO_;-zy^@Yo~Rvg9@oIAQUDfN`zT`^sGNdL5QJdQP7VT%k17#{69T zN16l4$Zd!L952yG!V}U-+&u>hq$mk+Ea~0bdCkG!zkyX%)b{rFfG#)Sz$d6K8S!X? z5zvJemKc$lI{{|!20DYFq$uuezHM9QR|Bd2m$-;Qbf87EB@qS`%Ss~dIZ_$BtM;-q z5kmdZAD)tcv$XAxW;O&8fo9e9%VZDU+Po*DSm#?rwLAYBd40a9!v0w8NxzCOj5<@ecr);#w;UB8Vj5|m(Ow{9?3qG4q8Xly%@B7c<%@!Zf4CL zYPFqSm>OgyKKXYsPi;N`c$OH~_$o)UEtPuE$nKz@A9aXmuFaHE0QjSB$0t-%Ts3r} z)KBtAnWp%M7U@}X9Nz}WG%4_^0(~zo`QxvWnoXvW5`JsCSdRlPtmHF$uS@mvRZKu7 zBopMvM7WbrH5k8%W18s@M`s}sozD_6^h%69T^{5V4y0NG`;uZ6iVG^m?0USbC{IB? zf0W-tV1$)MGwcY@WvKi|2sZ&%iCp8|Z*?TK8nDA+>c1Dx+zRekPK61H$s;M{ zP`TPEdH@@IsI~GVc3e4Qez{x!A~B;b0k*g=*CurtioKT-E@8Gg5ejM0OT&IxJht<+|t*b1G*>q3Gy6 z!^xDf5!UYTdXwAO(}%;79f_}gDVW+Aw2LA%owv97!lY$|8bB12qzH+Y3<8lKd@QUV zZrPUfl6z*?_*@NeMWfy|dX^VDvh4!&hx{2N#hw3Sw<3jnDP9g7dlF~wTKHs9iIl3* z{~m<2RH2Fl56`EhgpB8P1H{6@5~O3=iZUYouAK@UC2VWZajY-PN^tQ~dFw#}$CNP|d!;=O}*YzYx{gscl z%C_Xbw1ZotH)B@5!yW%G(2KHPx%F^`)iW;1TFGHNh{6hLY)@loYo5YDPJu!mhK3BZ zNBlE~TR|hQ{<`?nM6t1UX%%VTrq|sC`D`6OV85H^;;QlSl|lQ0hfxtG&@>~r(4#OV zt?1>EJXwdfC7E2Jh%KzhhfC!Nm(e{d!wmZTVfcl|>pOPv{`~gO^{2ASapbDMn7rU* z?3hgJc;0RyB0;+%u_mGMmxOCn)9DbV%5`}hBJOJ4#LD%(!Sl`Z0!fvt*P+x%W+1&g zshQls>B|}jX_fohDyf=K8Zz7HBIw>U-f4flXnp)6_)Y_mb3jxwcmOrQ@KhIHgoTSf z+^8~P>OsLnuBC)hARQC@!hdE*ZuYaN4<+mZhyY7*iU-wwjY7Fg(N@MCd z;*h%45oJE~rsSZY_~2_@*1AhcBBh)U{T9p+6u%8D0R;|8ZouB<4fl=ujYmB0lAAPQ z(~ZZ2etuO|dSMg&bfs*wwo+(LJi_Xbf8Svm<1QTz(%L_*`{Gl;8YRi8e|N(G_oJh* zsO|}NQ2hU}_D<22Ma|l9>~!35(n&hDjgD>Gwr$(CZL?$BwrwZ>?(>dwzH{-9@9Mi< zW9+r|S~cgas;8c+rze^?g2h06GdhG71==tG*=y}Jpi zp|tt6xvoOAlKr&EKId>I`JXqioRdyK708NCBU~rAU13EN2z0en> zs7odJ&?g76tD^#YL04-nf;+&`^Xcq#cPIXMWu z195j~S}Sd@5WybHp^~0|WRd8&MxW(vT?Ly<`jk8RK=MikUp22eqMSv)Jxt`who5p2%@| zb#&$R&^FxA@4ucV64mTKx1J7e=I^xMzvYG^h%8-Axp1O$bDpx5oxUY;(Fx6 z8fc{s1g{L3=pmUcJyGZi8SH~Pw4#K9(TYUXg?(={sjF!v-_1B*P+L#@^ul3W*(F8g zTSi1&?r6ACf=gx%f@(22U=}8s)*XHupyFSI?KfR$p0V>j3kLA2!<~aVcP50n%|mU1 zLLZk4xs9ZTH!6*otPzJq?{xTlR$&1$@HjdTlkuw&+cII#Q*{=rSjJn6Am$h0Au|?^ zke&{w>l6fmbR=WOLA)L zy6{{_!03GjP5@KWM%o3076c<@crvpK#r3>T| z#5I|7_hYfIr4t)t@=IrgA$UUeF9SmQeeu;O(ng?mQ*BV2aBwaTp{s z-JG$p!rwad?P(%CzOxTk_5~BK7NNverl&HF+1^fga(maep;1IhM@7WO)_ZeVefw}k zAQf8CVrU2>&u{TudBf1KT|Gbb<#o|0H7j*+>^)dnbySGeeu~41=T)rN? zKaIvbZftG@7%ODc4C%-l5ugm3&U<`(%i)?or&Ad+))X@tf=Xsj9 z{W3aQYSqvrmGB`el{obCtsR)#5rK)V=xGfhxPnJ21P45JZ`(nY)OODb{m7`H>##b< zRPqCxVBnwyMX+m|7y0;&vE_92vlIJ@W4fgj^C5*6+#Ml^%O4ne7ot0rw)_MKsbw zR9eg6kFQ}7ZpnyiD~vpPdHfbSx~{all+KfY8U<|hW} zGsaQMFeR#JUMo5k85tc)nAb>L48iR#^fMi_w6eZ&y9{&h+SYX%sSouk5Daq166Ck= z{d9K^8}6}S64v1jlZr1-unz*>&WM-A*s?1u?>Tx*i7zCYP87`>;j#7E%=XG)=Bi35 z+m3}eR&NUMzxi9P6g4Kq;?Rw^36_H!Da*Xa{0Bxw5-C$}ed5>@OH~7Diy^Jm9n*EV zya3I=@?)vax`)z;mK53`0R+4ETea?-dwi0!fe8a|T0?)6Bzv~+XI3P+64kC7RPiQc zuY9}<%J~W}Hynn|V3>9NYE`^Q5|T5h`=gJ5uso2Ts zSD3KhFfU!Udy!O;3ee`m$S)dM;xLtJZnASrFyrz;yKB^ZVIr6k3qQDq z#uVr?x7*|C*InazOmx1eJty6;6c=<1E;oWwOOeH9fKAEdX0bC&^i}I{w7Oyorn_Ni zY!-{EJ>=bUJ&IsjbJk^C59pI8*qyl$#?U;6&;oD74&1Co+yDAE>zzop zNW6*k`v=}e&M_$b?(x*|6Jj8pxY}oCNmi*420pt8cu27=BED0p47CsX#iaaIE?TNO zr`*Oi8Z2Dt#rWNyg8G-0bfB=`zx~H1!U^%N*wQ-H8znC>1VfscOHZr=Fn@!eEhMvX zrWvh0|b4U){;?D{>;D%0dB2 z(AwZE!c;~i4WRKUM2=;jg0pY`3L@ue%DDZ5CIgc}{uf9bRs^KHN2H_$_TG{vH=JKN zHWxIgji|_ixmYdi;FfZ-mh!=pOv1=IAj1Z8%c}=Bs{(zH%S}YdxybDO54^u-ReXRB z)CAPpb~kZ~h#?`$J~kEY@WbIq{1YL?WZ z#y-Y|LB?DLD~@iF$G)_~n=&%ZI+|;6HoY=1FMbdRMnVsPXCGa@b-Be|mg0q_9t zs0-6=0QZ23m4fx~-YIO2AYh0BO>xv5NNK5!5x)O!ReJHlP$DqhKcAs$w-)oGO8oE) zP6lxD2ujEQ3IL3&{-7=4J&uPq`8dEilve&64~p?CX4dCTYql)8_~)&sB~xldxgUTRbpzu_C2-5w|gs=$Y}y<5@v;ou?`186+f%W(l!ZH#{+a##X#KVRKZWoh{v^a&SVb z0p~BkpJ6lug+n%UrTEx*-N5rlTqSJbIVMlD?Qs zdu~-CVKab<5L#1nD~Ev6p!9xJ<-w`FulO|Lgm)nwtwDV!{R!yI`tJV5d!h$Nup};L z2e&QD#ss0DXO!@#6Sd!I0{ElgRgU;Ibcm>H11CUgg)mKWB$jzjLk^>1g2XZoum)E314r=wm{>H%Hfa3 zZBG}_@cv8RvLiWrQg;nl9nQwA^c{VJAPK58WIvAZEw{YlGwQ@IKCtH;29B9*S%Lpn zx^kDVehox(vzlHX{^^FNX(e}=CdQd^tl|$^Hn@em5um> zLMc;PMsE$4Rlc743#uf8^rX%joOI1wsOW%qZ><6w zJ8}4jFo~sGcAeK$kxdRFp$mp+tDP_Id(y%J@JVZv8xa1aWbXRjDU%P4gm7qQ9>BmB zI9}xZOd;Nz(^0Pd5$MY7ayAnT$uwGHb43wpO9eQ^sd8mvLY7JHgaX5Nqbr-L%$TDW zZj2b3q;XaI?~K=y8~5wsJ!5$i?i&>D+-ZhFF2`UYeToaXOlg?&q%+^R;CT|o^>5mk z9FeJg2eiCH-$ON#??){qhf~Far59BPYuo6dqlPbTX-`Xb(!5MWzgDmvfKXLa%Ejyk zaieph4_41?xMz=}5&aMdieQLSsxo$QH6bE~P1rq&01bg(Ae1812Xf=|57qjl_z-}g zLZC2Yts(*0RBuB5SvhgK%~eSrgt}hPCnSgW2T5x`jx?9#JTm3cFHj4}c{49Cn`Q}B zLYJ6oBmSIbCO9$kD&_aCCr=(Tly7cnkA~{M16ydc2&_1g_bXYZ(T&9ODEHUuZ;J@K z`%*0qx;(IP3NW5*nwLwNw2<1mCy8>6TTQ7H*DQH%5iVsH)^XCYVgXSZtSr7)PuCOQ zUu;X)(uM;aLbJcM4c7OxPR=EbT|359$#W~O`Dm`L`kJlu9-zpC&NMkb3oX$qOzv3)SiIA|b@L zlLS}c^&f-qW}6C!q2dZ%wOuZDYKHuTY8 z(0b^(P-Tv}R>s}?AxntKMDG?ah<--N=Lb+gJ!@_QEvp0s6X7&UbI z5(%0>@as2l@CCZ}6_+^r@IS99Q#j%7#r>w8{Zc9MFI08-T|Yq%m9npZ(K!?1#to9A z2+SifUC@A?Mt|wioD(HzawI96AcHx_4Q2wL+tZJ)<2^KxwHyY{6b;OD!V|gmxJeI= z+_%KwJSY4kr$gA0uyj+M&O%HFWHP(k|LUkFGR+-PXhc*w(mSM2hLHMupBo5Humn?S zVvC0fBmQrw&e2V@6`=}iw82EWz=sPr7Pan`e02LIPk~7RvMQDYgF$l(@w~m)y`b@> zL-C?Y0Nd*%*wyh|b(jj#pFu-$Mw2m?6aLjVD_0*i+IAYO@iBGEQ#rEBc=bNkXuT&f zRu1YjL0_RU9coYrP&Q`V;lQ8P(+@0)>Kvpg7d%BXs=DFHs+X{YelX0%=5!|yg;Yfg zrn1N}KR|PV9)1s)_YQzaIm^gc2`VlLkqrnC;&DmovJPw$5kkPUp^D!NE6a_vAr5R2 zGfV-E9+T0(K_HL?IuM}6`Fs!5r9wqNR*ttXRCq5ZzYUY#%@>x7UTXq2HFJDYY6D;d zEk?vb?*M8VAUFs_ToqHR1lMVC+-o2RNIU3>jAO>lu3(ewyk!*N%^0nUmBC!@KrN5x zp|iTPg;=lD{o{eaG{*nJeA1gTiBl&h>|p+hY8>^6wQcWUc2vplVSvvmLp*1?1NL=X zOh7Z0tWQ#=^Jl#2@|>;c`6vOeNgf{T@!Kx+#g5TG#R#63GbpA+)EQwlJZbv+0u0 z;=D%t-c_!+irv|ha`j?zKX2$@*Q;QW0!OM~Egqf>EWpfHRocUwZn`}RaQ$FE5fkV8 zoUJej;3u=_9AxYs7`BGE83zQn5_JO90Xws6F?}kKGSvlCkCYlUB#h_ZsuKJd zhMQrMrdn5RziI)o&4ifpUIx)>_z*R33SS8rvL9EM4?sLY&^xbh_mUQ4xf`2%I5JOv zG>pmp2#+Tl7NB#WnwLC*zXIc<@M|XGi`04EcfBFz_-C6p0 zCy6bcy`(UmO`fNf;!pFbP#1D28wxPXHR8@oI_n_|ahZA*gSC07;vqHH-Wr|ls`wN$ zmY`X~gvzwp>UQ!37^?X1;sqGZUR+i_m7lO4??cuk_KY9Qox_ij3l` z-!!!d)ZrQYdrmA*=Y5qU#S>a90rA>WFSQry#gX{K;nNwrXs?jlU#=ngm+Nvv$ck+H zdP(N*w{|P0sHtlma+S4hl52qVP5Z|`jQ_yr)QH$vupUjwIreYO2tyEf5r?-x3{h4Z zhdXZ3um_iyG=Bf#yvxp%di$r%WyAUE)~~Y7FRd?i`hcK}7+d;1B-Qi+;<(&n5)?OJ z0eND*=B;>2E2zr-kh2)Z%%}yq_7lnyLg+Yy|0}Y%t6V;4@NIOyZI=sggVi3jwuk;sm0H5-C+;UvkR-ZcClz)Uy-)og5!TPguxQEzXG zn|37|6VHj)z5{J#@noi zfa%dVz)1m+i02APyQNhQbV@SpM&@J^-7+jxU(-L_%dW-b2;l6%<~H`tZzFlL z3l(09fUTBPiA5X^-O@b_@)RmGoVl9%67H^aFHl<8)+pe|6h)|ZKOj0mC`+YJFl#|L z1}DBEF`!7S^unH0Qpj&?vGKF6t|w3Y4p2dI3sZDEA}rEkZg08Y+Xin~@lyGYx4?FF z^n`AB(wMJQ;SLuiX#^Y^IEw#(0aj;w2NN6sI`Az?l19fvz8dZpR1wvma51(FPo`|K z#FimU9Ehk^)YtaK=MGu)Lpe>p^DrcF318pxTdZ=`F1Fw2`Zy-aV%13i)|3o+2S&wb z_dUvk-R_CYWLoQ}SE9Rqr~plXS$B#OfPsQ%9+aH7Kznh3r+;Z#!J7B5cv#(GYGP#oX0(qu%kNnN5?#5@YJY%mMVjr9%v78!IfV%p+)Lm# zPo}iyUCn~^WEz{uWJ`lez3oHI0PvB}*z8yheN%Y)?wTP}f8Q|UcL#yxJcwzn{ar!+ zrG()X85Q)4>yPoylm^?!Ybv}BKQ=xywLoMvY+2?lU!l_}#|m#hH;3apm&w%yQ5#MY zbL&s~klhG8{~%5!PDw+)lD)#L{M|6e{6L6o>J;fW_KvZVBI-2PWc}+a+~5|Ag{ezB zsM|<@RNwyTY1(=};vV}uzl(gaW)NwNi}f}?-)TJ=Dhw)&(cL%Zr-J?Gn$m|j_|eFU zdEmlC+-0~wsZ&_P#t0_wKZqc*sb(*O!fpx{rFmqVeV_FBr0jp72mb+Zdj%ZQA*SPb zhszf|vGqcrETq_X`&&Z5e|EUrJ#?^;r>Pw>H{6~OL&ew?L zHhjYpn-?IXlr}mUrc%yqkx5#Q7G#%T5r@c+LHb{6Y=9VeVlUGNhpSabJU2?y+KBRJ zqFQDUBH=Y-!A0%%O2WT4Bp$t(Rzvl0W-ox8+*6fQUKTxg+PY3_dI5@~<*aM?hkJm^ z8`~zUW!~r9I2=28K=p|hPV8iAHL#(h{!hjYwGW8TsOV#D_klQ{a!A!v7M+mW+B}#o zT(tJ;!2Zc99^^Or4Wz)6j74SMa=O}nGk)F)_9n2zno9N#m``H;!`(*E57emw=~$2z zC53#BUEUS|InTPg^>08%&7CF?aYztQ3(Y&cn;vH?ZxMEL2Dg~%8b9_kZsR743#WP0ajr}scB%Mb z2T2yU4vGxG0TUIvkc-5+Zxgn{!9}z$lE_e+LoZ}wtA)xyH^B9Lf=2Kl_WGJ{K9g0y zp6y^e=c%mz{x=su%E5!{HOG*GgmD1J>$lQ3>G=;QaxCLMhP2uF#toOj{@dcymSEyK!(IeT%*dUZI@0O z$)OvC$8sxr{0N)B09cNG<(@R-XTVxxrfVdXjLNM%92ZAN*x~v2UbA9OH&T2VlyCNk z7bSENiNRTNk>Tzc6;^XRE)uh;nqtxwR#;1n-3>3e6hu@(JIV&{Hzc4Jsd(K<^;QZO zN1?B2smOGxh1{D3T62vjW;Fp)UrC?1>vK{z6|KNIWp}}@w*TN3+&hCk?UYE1tfiBZ zC!MwB*)1UWe?^n!BbT=TT#I0Cher{W zeDqpV#cpx1xSw+7<~#fQ(`If-4=Yv^3L1ZAJUUg7NzA4trhTdpzH{%ecD!g#fh=L2 zAmE^ELpF(f76W8w5~Io!7dVH5$R-2><8kM&l=2+%79((-_@{ngecl*@m5gYwo`$gD zWEbZ#kLQ327otG z=(O1jYyrjTzDLB(4gU&pY5Z*rqy|9Y# zBYdwIxG52o7E@Xq_V?bJ0Wr%UfbFKks}7;cdr9qbW`VW*f(10r!MMW45qc~DQ;d2` zDbW^hwhy6RZId=NkmSMcL>v$HH}6TX8(%A~)G6SU^BU1*517%!KmAe9wdITrU}6!O zi6qdEk9}!mEchLwo&#~2Cho!U#DYwr^uZ?dv~N9;X2p!@GoGu=>@`0gPLNmQK~w&V zq!U8#BA@p%uB-OM)oXMCgV6oEYlqZMQ$|v2;#_B_T<_&S4`wGpX@sYb1<}=pcaiuj zxKD^wo6wF?V3s;`M;F{rcE{+9o)^Z_T5VF1KWcA&6*|F&Z+`?#cF5Q>Du-qH2)IYT zWI|kx#*L$2sSqyvWcAgrqnXZjk`P-(aax*e6nGHnv$x!`5DQ@Zw#I zot7)Btt*O?WMx0R6H+La0+e7u-^iXK-~H7{$LET^QOn&`Z%$^I-loGmx;6o#G;uW; z>ro=wJ#my!|0NqMt38)=0bJ~BX?ga zWiXo;)0{s|kTu!T10;qRE51=TmLv1c^A6CTuZALb7i;DG+hZv)C(-n0PG?RXW$-8y zDH36DU1F~GOcfCUy@iR$%IbI-$pi9v{A%6cUPF$5XVs@K1t?P+O_>rvmgso~o+f3I z^L!>2d%TS%%NIX9KYlb9Va*@`w!qpjCg7f2o7~{yO6g+)L1>2^@CBn=-IAGVDGdGM zwzhMU(yq_CW)1qLGborG$udLPxsok$6V1JUe~7~A-a(@77|bOIhu@Sr?7GOnvE za9AoxA*~S?+D*O+X>h!pF=j{=Mr$gB+#fw>HD=CO@j9pfK4ulHxY z3H$jka=bAfpI2TVe|c-VguW+Pkoqveoxnkewm>ca?Z1a?4QHGTPb=5~Z|DU2y|tI~ zy;oZ^ABJEKsS7b6j6M`tvD)GQ2r=%c3}8vZJB9xF)ir31JC9%VwDGjEg3fX0ZdbCa z;K-WXuYbt#nM8aFmdj8!mXZf?ffzNnVT#3N#VN9qVaL%O_*BB=P#UBL0|BQ9hj->9DplofZ5&J=gCdC`HC8fx$OGGqt((^Y$a%;x#6 zLHTwf-Y4bulGu+wYe{>TEtGr76#52-8c~Sbg*l+%>xfV9A|IYF9MA;Kon^|t!7mv& zUrx*w$~Jqpfw)E3&4!ZOL!FljWbDTAn$DQ-q@P$zl1;_vIUlvDEJE3v*?kC+_wB@{hMx@Rs$E8~MF2dl}dh63pDueLS4Iq-b0Bo96;g{uQ7p1+Jn!svnzSMWC%E zPB*(Yk?GJT^oj>pjV}I8{k^m0hB*lsAeHd)zkt-H1ptt`z`J+1>aio2gse=< z_|E?W-y;f_X36&GiOA6xiN%vvdZ_f6U1t#dI^`nyus^&5Nw z-y61O+eCizj@X$s1nnX>pC?}6{F`K}h17<##4Dh}u51?Qy3JvwmeU_1ietX&4g6>_ zYkZs8L;(~CUh^%etVfebSua4QDqHe9f0YsG5{~>58uJ6qYG_jbb%bXEQdVPcM*&pC z43Pq0gK$Io&<&U^YcQls zpy|}b4e%4h&7I4gAmcFtsx2J4!F2R0#?Jv^B;`yT=pOhbWqb2fpvd9%Iakotn(0Th zoa=cF+l`|N1KF>{5{WUHLwg&(+Ply~Ex^lMtN$1SXWbMM9<_b^nG9d1IdQj&Y}o{# z?OjCns3|je++r5mF}ABPn;Uq8%L!$%FD1qZ^nXxQQ~9cbM#rJdVKP+TKQh7KMW%4CqnXhdm9RUG6P0Nw0;+Bvumvvj%CU>b#d4rQCLimo4e zm}cCy+B)&1DQC%OTad#1iV%jSNt_rO=!7h5a6~k3Mj> z)^vQHb~x&Wwt;^SeM6)21AD0cd6S=;KNqjx-CS$I`_1hhGPX3my`Rwvwo|<^;FE&d zx^OR9qLL4S0t>(4&XVk|U!1)xcUk zk)gWwdqRrpO>y|K?Ia2Lnn6f+pC(#lu^`%OY5~mTy>8mEr*UJW&esff*={Ety1Pl8 zUf0{f{B@lh#h2+PIAPTX5TEh+fIA; zNuZc{AE`r!T6Aun3FC6wOs=#*7DeRNhY`Ik6>6=cX>UUNZMQQK?oM4g9mjcX7UY>~ z{b$5I`YJ7K&SUGEKAGlztqKztAD9}NZ*_+HM43vtF&mR7(gkcvZXgmNip8-YjVj)` z&%>}`HjFXX9Pf8yLh<4fo#j3wv1j-w zxvJZ|FSZ}5%8S~fDSOrn=NJ=rvy7+TQdGF-$$fubW6x9c$>%!>w2Mhz8c!q-qxN3_ zvX~pEvLVRL?$(*@!x1Jv-t1|3?(CZvXj2b-*DBN;N+3A*rHYQhk&`s|=FM)X-mGFE^os_{eZ; zJ)C%}PU6)Pcl((fYr5}O1Dz|H-K44~H8_1tH{}fh%OYhwVvk#Dc~d=~5i1O=S}^q3 z)$8egNBL74zmH|Ywqibq!l{$qW3o~xVGsXSYTH9nlO+i_Bi@*rrHNczm%gIJXc&SH z18%xH^~nxUJNkM{Dy@Bj&imYnJs75?mk``z_D*X~epeE?v5RGf$rat~c6_VDg*CA} z+{BEstLBb(YX_fDtq-T?)Th(+@A4rEX0D7$DMMC@gYe|m8T?3-P~&iirT3ldgU%5z zvYRM2RWTmce%@Q0&l|W6dN1m&8kH3`oW60${C@+XsHh;;V;mT-zlb&KPq}XbGJHJ6 z3E0)}JC~`Kt}q8fs@{SBjiSua0cPpv8pC<57L1oFZ;JE z3|S4@ZUI?J=EYeO8K4LtQ;!B)?SFHa>ne`#7MSC_(bt^{>ujt}7;R;E1q^x!0j{S3 z1RBn781x_OTgoE_gxNP(eE>Kg9-{-4s}k-29~ry3obT_-jUJ2Plnt7pZ1-T!bnBa@ zKyLn!E_@v`X*wvMz+C*f*1{{c^1HZ00@v!v!K3xI1O zm`w-}Ck;g0LlgZOFe33=<91P0IbW1OZFT5cX*y1G8lXV9C?-qa6UI6D5S>%UY6>$B zkvz=MG7Nx{UqcP)3uUaEqjC%>yK$gNy43(BWBULwK(TZ05x_mcAC2z4#PHhDyQ4)- zWp`6(m&Z+SG!uhIaL}eZ|HydUk>T-j0V8E_->O2{rY(>9Pey#VJu21NzZJBf+ID4Q zJ(RJpT}Ax~;gaj0dY>m!ekWF=6}mtC{LLCRmf%j zA`tW@>K&*|$gql25mU~$11Mz2;WD)U9DUR@%u1%jCcWPbDt|avK@l0%LD~!Yjhc`j z%UU#^G%O6PST4O;9QEpCN=g!mDI$AH&SWd^PY^xcGp%=*KbhH@es!yLi@Ae7OlfDr24@(R?T_Ywa zZKM9_nDvV(P@`t%Hvz5>&G3bj0J%jnmv9pG;JAw9o0>;h!p~egGO^civ^vpMgiE0# zpOrZ3#iNGy8s7910Z&eQ63!{@L+wgnGQrz7E3*T~Z0ert{f#UzCh0@duR&3FMHg{* z0mJs3ww+sY?-zQwkYWdng<_^745-G=k#|s)`l}w{hg;UkB0p$?JM2+?#Mh)mKHj8t zwJ=P8(kMZFjOO%U#jO4Di1btN`%M}_%P?W!Z9=ZTFjMuy`D%I+KDE*171UX?BMFBi zRZb-LpEPTtG_BtBP+W&px^7_4p0Jv9|`WA-L?GfY2t2G5-gjO>vP)vc$~A9 z;HM)YUPQ42!Bk2t7Pjum0QeVz$JhQ8D#9dzBecIGb{_$Zuv^L#;u(Nss&>jp);P9$ zv*jd!WNq((K`3(S=ITz=VEp~JTA?KrRPv$=x_mpUce8x=7i$Q+F#0R&IO)_*h?k0M zWn-Re6~gJeo5k2lq4YUZtSz81vQl%>#zV%IU@WB9!g&5y|H3qY_w$y8ulzlBRdC$4 zzYsSF%iE{W&$u25`yTga)5LDU1&nvPEFuepZ@j8YB9*}e6td6YZ(o%7B#)kMif*_m z(52RwHfIRdmV zXDo-6)5=5*xLkGNLJE+k+!ebk=6nE$Z8`4EJ)1*9?m*_vgY&g~+VKaPTL?{n#g0`0>Disx6sBce zEOvipLD$%t->2F`E#7A_d_myT?~0-6;%g`gWhslu1{l8S0E7Ei{TUME3YL;vQtBH! zr(Q;@$lpN($=}Kd#n*f5U@X?cDM*`kF3!WmQjHY!doJB)oH?*&45CeXLU6Adt7O8bl5Ju|H$Nl;wf`K%<>w^Jd4qD@h?a`t^@8@y3 z`pSbk$1lvG(C0D%xYImE-AGdTUr6XNBEBjnAeHmo)bRg*2^3+jW2xZ&ocNFx`$ShT zd~J7q4&!ZhBe_k^r;Tk9cu>{^!Nm`Hj#`y~wJ9`g{jl&wlkS{Y%6}eWL|Pu17^dDo zzRI+cc#7~k!BS{HZuU`gO708&f78Xps*5YMGla{MXL;EM+c6o{+U}|1!o({(u^H@- zfXYjw>0c9eKip4|+yS$rY6MDpKTWm!7(T_+qw2U-X=b%I$BOTd7Sh&2iqWWnc_HA~ zq{j&?R=ul$FS(gcuCMj>LaAHfwWn^@q|?B%;07`?`)AO^+iA3g6)-(3yU5@Q47i;IM;sLO);JDW6|>Vwc6tmr zU&5>&iWnJ&^9X25%C%tNee+!nGCxKM2*y+XF^G$@g-VdK8t=WGO?5Dwj|{S9cSV|b zloAoYHAQ#`+_wX$9)6>6EN=GzU^+v?xIk18Z$jx0|GPj~6bkkTY#C>9B zz?$c1v~v6E9g`sSafA zO)JbQmKuV_eC^A&g2WhasZzuz&lZkpFAi_*TT`*2yCkylv&0&t#s%7XzdKX2GNECp z7eGAZ?y3MU z1VfY4S2+abr+TludhXv?NBcAT9klbbf#1mbx6zd3J&luT>JYkCdu-QBZ$JrV01h-} z>f(sE3k4qJqUb>lDvkh95uls3UR!Y>E zZiD5TA;+mns%>^n-Wbb!IJl-(L>|8ai55$Xl66X4hq;;j_nR;P8Tk_>L1h2pU zq;nRx(ZBHCsX**7sh~HYMRu1Cu{v~jG}i`pxi^ij!kWIA4l!smhmg`r9LUrhS*e$MUjuiD<)ab%oI&ctv@W`28tWY=*Co_?FG;qeI&4w-ey=8pdScc1#_IxP2MP3QAQMyc@dRSmG_no22u|ypd za7VCAJ1Af5CeSG%BkTOj4cMcpL0#hCZ8&hw&9irDVSu938OOIApF zp}fIJTT@Hb4;d9cV>Ig8hoWVwvi|vs@HZoO%97W?K-O32mzBC(ozv~Ir1N)TyR^zG zlM|_(pO>jz=dVvpbbiAmL;3@}wp9R|p$JU99{HXWP>3q)I(yWt7JAL>gPVR9uHVbD z{%EjZ*8~cH*PT>Oq73<70f%l-oEt?Dw8T zCrj3H+>`FK?3$9v-_W0Mn2gCk9*0T3k^ctYEm6z}IS`Hc2I+8PEt18s?_4v6u6JlK zdi2}jEtLjIl^4o??sINLLB@PD7fXX<1BE}IPkwb3yqaxWZCM~szm;Xweb@rSYc25g zIT$buh#=$P1xd*oV1b>n<5eGj?QX9)SO3f!SLcP-H@B&`(xe^2fiC=Z;U-VvMo~p| zMOG9HD(XVRQJuP>O$OCHI+4;nl#axlkJm-GKj?-L$FYbp%(ez*Os>?Qh{k|R)xF*h z)q_9ZH!2srT#LMQQ1s+C zn$2dIgWc)bf}diY)_Z605d@pHm+5&-3dlE1M!+;DaAjW<=^tHqa+H z)RJjFOJo=O{Y65GXMLnK-^Q`cJZd)zhR6$PVFNr6-QH=SNtU>_HX>qva>}l5f}xsA zDj}jjLQ((5#ZQ8_jy8XAxxQ0HU@04eL!&@h;FC0@;;@tjhPm%UZ3;eb!AJ73LeS{j zYh~%-ZaOZ(8(wCzc8;`B@$p+kC`fZD`q`lJm>&t=XuTP(1KDiQ7wEL0wggQJpBtsS z&dU9Ar1}fA2V1BB&Yd+pg>)CAh}((8I!{_TSt)f_?wPT8>65A;O7Czv@sC3~1KFj* zAt#-)TL`+fw$ca+zK4UP`f{&1xPIFue zB=^6_a1c13o%Av$`EFJYEThomL-U`{FA{)6? zs}<7qt}lf9nsU-QKVVqC&!vbtiODX=ugs#qUV!`XLS&~vX14Ywngl1jxXBWWZPNPY zaCt>uUTf~TEUzM~Kpf@J+YpNeR)>KVT7F8Z$z=qR((kECPo4}0zH7ZaokJutMIB%J zSnJwSgh_~dNHh@{QL^>d(_NYMN}vq;j6>2t)gV9Uu!Rd-Bg;-m-^Gns1+x)O1>O3J zd^9){_NX-*N=uQZEonj#)C1s<$P@t0p{FyxN)@pldGNjvtX((myvwd$duDug`w2d?SmYFd#%uuQfCgEbSh zI%ObL`L_TU@_G;4eG@Rc+A`8-mr312CzEt|+9+aZP1S|0D+{WVZc~oyj`z93Hrn$e z8NIm}<3?D~gBky}%!ac50gC2QCh>6hl|uK=;f*H6yikX}O+a5-(2ty0`O;z<-7^Yo zp2~~Jt2Mmjs#brs)o9l=KR`XBTLUv#qv8rRCeeMa>%X}GZ3D0OVjA+MmbTB1Lz@1y zHA4R3ZBiadIYW*ngJ{H0ev=q1Z79UBOJMT+P`C2(CiK1=zEHOuk?b0B{$YUjVsrr0 zqejF(Y;W;omi(f&y(JDUK^ZX(NY~Fnm)c$WTu4EMSvE78(L|sAUPD<1e+VH=ckkgR z{`+G7;!cezqxH{mktaPK-!){&94xkUpwzwfa?ZyXNrTnO%LUB^V1xoogk%kUcJ?kv zPy{nF`A#aE=ghH05;SuCyGGtTH(i?HdJ8$9c5Y=|g?gUPlINmuDdp%Yn3N%d)DK&%?P|t)8z8+1c4` z+;9Zh4YZD=Mq^5@cdo}z)L@A;5&U_4d9ozmIkUXP%QaeqHHx~?kyXN?lQ^r@b)wfp z0@errm}L7VlB?nJdmo+u107u*9te-ee>g_-yL_h+t#iA5Kp~?envHt3xyE_raS|)Y z0UG-35~v^u?sx$~UMisdmUmS7gV*C3cWGgD$nGP9Z)Mz%Fc&H`e2;%Htih>gq3hYa z$+`+w1-D84ncohfFw|2m8wf)(kZ;y&v=`hJ#)PjHn1=pIp-0Cb4ZC-z^Hkzlk(N(4d~58~dYkw{a1 zU>G57f`c5P*AEmUd_Y6{d&+h(#hAC9it0ie(&aG(GU!P*@4;9ZiYEMWv8rf)fLDR( zk|WgimefdDG7N!WbGcf>Q$)^uiOd-9-F@u=EPGy$bPms}xXZ!wU~l_OL{0~i%x_s# zn<8iIoJ?zfSNQ*WsW0NB@HM(0(brRr3Uahp3=}(pK^#>lTP?VYmP*&n-k=T_;)w&J zQy>C-Uhmk&QJ-lXU+Z=)^wR30egIkY%&Y~}v2gNJA_T_5LqnS4=T-xJ7OS&}d(N*i zHIdX`Y@+9VI(zPYC7oG=D{3Cq8)lRWjaaU-E*g^9 zHmzX0+Kpq&6IXxlegwpd)p`WR3Ms^n+s;oi9T|Bh zgA!3onX!7*ZF;0PL+jzb z7O*?~ttT{|co*6aoGe`J?b+vBHuLNi5Gn!2Ae1nC z@ZT9K)$AfijbTtWJfw@R!@MiAx}!KM){yGVNjwTH=ZGO9-=bX3d`*D8ms#UvIt+nQy zW8C8!_sB#SOQSE77jSitOFXSqD8Du5rK}Vbw;NHV{4i*^?%~3!IVCt-p)n9mLpidl zDg54&@Na#3w4VpiC?o>C@-^i5&^WTf-z3F6k0=l`m1g+kXRVM0KYtek5g}0FBBrk1 zTA(vtFf_#w4Ci-K@6zsIeiRboY1Ac@_!Bd%b7yL(#HIte60KbL{+xjmtVtO*e|CTW zO3a_Ouu@^l?Dm64JCa{tN?#MAIpxNVW}EDg(R78-k`HI_4Elk)tvl<6nEM0t3{~gEUsl9kv6sy-4kaV?Uc;Q1Bu8Q)9Q*m; z_g;Ofp0A%otOME@0k4dym@=0{T)sugk9Fs#1nl-7oY9sZb=J~!5~W~s-0Yp1&s3fJ za~W9l4*g~0dV>$Qg{BJVF|6D%J}tK}>=;rJ^77oPh=#r0?n@-9FeKbNPpQk)%lBU& zGt(5>omEAnFU9A0LVjK9$z_X4PU_zc4usxzHKM^ZCVsd$_)W*^tVcW~D zIFmnqqlYUIma+P6CQIpixbhTIn+3B8%h=A+UX)PakNv* zLKBBXF7gf*m!cCEH1ay@y$=>N*vGNY7W&t;^}^6EOy+ApP|OI$DG+xJea)^Uy2aR?g6Gy|o#cJCzhVnC4WPk@s5B_d4j*xNsazS+)T zQV>iU%cP0ccp$3p4Yd*q0`5$Ua+gUThi7f3ly@4%%ZV)<(|RYlOy5-M?CQ<*8!B(* zXRQJ)!89+=;M!llZFT@tJkD|_;hz~~2Qw(tCUWd*YvPLVB7heQH?MbsUi=F6(Pjjt zG5@hXJm(#pqRjfw!ZuW6flXxF=@|Dqve}|a7Fh0@4wqP2XRB?4#bZ|r+Bz$f?|~Xs zdRob_z}&vRH&Xl|=<3rf6?hl6!NzSlQ8uX!V|2V9_&J9Ql563~atw9(eI|^_fHCdu zp;8vy<%jhzh!^QYJ{mThKjSDU)Lih=x-|bbi;|{mGX&9Q6xwg;KOnYd)6)xwB1T?} zk9MX6d2GrWpRG`_I|7H}oKCOPR(=#c)|@mIgzt~EnprlVPyGBex+A|vD&yPi<+Cfn zWX}Fwfn*1zg`+BsJVrXh%hBt%94z;4gCbV z6-A_sbbn-@r^D6{R;Sc0B9Y1zQfy1caFm4GtKaFx`{SB2!^lIYUYZ8PmOcj zE#1d*-OZ$=ey72CLHo%pXVd4HOY$3`9{OOU$n#WQ@-Jb&%n*|KN!bGD?B%(sp5e9SMfARF~xa`-cy?Rr^nTo%q@bJQLiJU5z{2YnWfzu-P|WJK~F4zi_v zt2dASTtaNdh4?WM(c&6_%tx@RgGnZ_x1At@iYZjC5st{OA5vmQ?Tz0B^)P;gJ%@+H zg^na!eh~iL7eY}Td3>*Uj}y`HciIBS(ww=0qDwJ9Gc(x2BW!b1!)O+=7J?L?!7JWaH3O4- zdol6|I75>!hZiDo{0#6u0bH8Li}TSxeGGWVuvH%Upu~5^_ee&;>cV)ARbD7ONM#NC z=uFsMJlWs|=?=o2m|nc)&>*zoRl8PuJ`^!q-0v9=WpodG7rvi@59UvhD+jLIF-31L zrH;SZAHWX*UVNFN6}%t})FMdV)AXJX!AYst`mXD`9Q4+iNiPwGI>eB;rT#)wh9$Z9 ztZvqsJ=)RgbWF@!G=)gj1iWmH!@pfYyx71?yoid5jRihCnoq^q@$pH#K=b$IWerW& z3XmP>hHO`alV@%IImKN4Ml+uUW0fKIh17Z-xHKNCiEC1~t0LNoI)i+B$az2z(f{0M ze)Z@!k;(JAbNIIZJ+p)K6rG4~R9YEc!7Kao55aL!!qBrWCheZ1L%{E3C92MjxkCpp zz9JJ64$OVP_2)--(CttRWjSW{1Hlu#J>F>xAe^v$}-Gt!}c^^T|-x&3#(|#D^ zLw1~$ep9yi#ztu~r8?+qk{)thAor%WLEE!cIN<_Vu=>d#*H0YmURy%DrTgUCl^FP9 zNPUVfv6nL3!l2YL*zQn^t-RAF9B}v`FbB*2#88gGm zP;)eljWtN^q808aiQk7xd! z%gY%u&A#_6%o>trtc-WAt+yR2GSm@A0-;d?v1%*B7Newf|Jb3S1+hH~~8YNg!C}EBn3C^<7YvQX>U?MfK?H zVq9SYezlLt`CO>#BlJRZ3J!`TnBDetF=0(xjW0`7Ai^{+V2p`IttbQu4O$cnoI$_F zw0aOs4v5jSfpWncA?lyHWi_jYz7}Jo$ybnz?RYZhOE3sBuS(Zu-dKX8;-U)il2S`Y z97B236ci?pRns>y3h@wVf6F{g8lUITJs0qHr8iwDE2yT8RybRwBzFabxKd?T1#jzr^d@+>Yce+p+JX!jsQf(!Qp4bgEaG_+(5n0wfK|D5y&r z0hbJeMXkDKt6}p)8U?M3Av0Nkz8cxh0vf?RFSnfVx=t4^RH7oIJ$6}(e^BP&{#^?> zUHW95hRh}L^@HPd^3%bTV!Hd-Kog)RS)0B=mYvxUkIN-v+bnX>rkt0V@+1o1qs8_b z8D<|(7d7T+>c}y>K0Dt-|LKEKpS9y^O!eI;QLRNOw^VZE)xeg@EbO6|!Y^~as1`dL z(5*`d15C2-rJPSMhP~ZMpn>=B?vhc`eedTSp^Qvv-Yv z0H;_|if;+O6RHs^v|PGWla{xb`&8YC4!iU8_(Wnb#$9Y|6CfcUc$0+7?m-m7PKP8l zh5WvV{4u>U)9xuSlU}Ht16Kdb6s65svKVNGLJ4Z&1KZmX`a{9%y?Rjw$O?dT%0u|sbj|1C;Mu6mB>Qp8yweJzgvY7MrTTg%IQ!52u z+>c*tACH3Xe({u35Eu^iS_7v9&*nE${*F3vds>xTvbXE2`D(57WX+%(@f=3BezI#` zK*IeC(jUjl)HG|e(3`bL@GuFDr#74pGug!QG>-e-is6gPxhYc#_(8ve;rWnf`+7w5 zB5khWwSwndBU;nhc!C?Ab>x3a129}W>9Bu%f?&^V}K)q1LfSroqW zB>4Y|TwQQb_>1$v(8!}iB78F9O@GozEVjTu?5 zsZwim1^G^bd`rv*fg;4kW*JzA=(i~Y?ZtuAo4hFkWz5->zf+*I7`tcK+fr+zyB%!kng0Gegyd`k zsuN*J$}|EIzTEESPCxyUKNUl~E=s;V2xOY<-^zK9v+u|i;5q=Z)+AT2{R8^QLO$8; z?!Kc_se0MHPSNqncM6iA!9u|XG9G^(zmvD%+Nag-bJylu-Jh@xU)4Srgb7e?-({WU zmEZD4-KMfwNER0#-gp!PaZAzbZX9U4{w-i@PE33rdv?hMkK+BYuQa@Ldw%o-;gOjEVV9w-FVI6sSv>`jtVL;Y zfsXx9pZz=PA7@=J0gz+YcpaI~72(I*xZ;wIQ*IM{jYWmYJfh1r;@Xf!g^z#i<*43N zkh(#!BcXRDS${384($OWOUJPN4U&GW=HEcA!M#5XaY|IMUP;NN=mnJjglg+tZ*@7u zXjvDzKIS_X%ECAS#8Z)Z-Z;s51oxbfG(fZp&dl~!G$4!=Jw1Y z?uC_$Z1TXz40CY2D%^kD0gVLKWHRmdYe)yg>P_PH;ahb%@i0$KBGt3 zs^Q(>{^nO9>Tr(j1UX1WsH->5(?RL2%O9G{KXY=2q3ypAfwcH}38K6k2h5|j9VgxF z-$2kSBw~w`L!J`NGj12>~N17f0hZ=Z&S%e(#8}7$O4K zudUt_z_MMR%APscC?SWXkgfC(g;y5YI`~(UvUL1hgsI9Bp2-0&kmCnLay9F-v!D#C z=(pH7rQTz{WwEN6As>NOemJir+%oiiNr-piLn6@o!-GM0V$jmK=iu_wK58(BdLK#Y z`i6|lYVl~_5+Iho((HrY7Ue*NLoK;b&=)g(R~!o{$Yk9iTE(O_KDGJ$Udhsv^CAY1 z$KoRzHRzMt#z$jd-EBwvH5eHQ&73(|de&UO08Gx{MDB-daKF<)F`OPhI0>bz!Z?Fn z__Y8RkQKmYQWf|;7Az?0T&)!VY2EaO{jj|FhF%FhW>-3!B9H36V^#q<4uLq4HkgXa z_RS6FD|xkjiC7bZ;jvZ^EQv<%q>b@}pA{Zb)R#aGl2j>!<^EQ+GDEjYMTeU@V^;_{ zFoG_8&jbCN&c_j4GvbMA&k+K*hO4olIZZ4s0+Wo6gvU zSthXb(!ueZ`_1`NW|#@Yv>+UFxHF%RYUT<{U$HTz)Vxy*JQB%6Ktqkr`!v1hS$X{yC*F z{Zfi(>3@LG2eRE1)U~;-D2KM1Xg%QeF5zGGY+=JY1*Y*;>J0#M`YSbtw(QN6;7e_4 zoaX3Ncq+xa#Iv^aae8xDBvUxqQD(J|q*PE?J`&X7+(hf6a|ThmGQrOs5swIIRL;Ls}% z-|n3ueEP5ydt{KjqDARBzSpgF9PmllVPt}+ENX+29Xyi=}ryceHc%s$@`kG=&9BVUg!nnx8t&^gtdaV8g81sbVosp^Z z6X#ck>zR34uwKxlA|+S)HiPh1q2XpX1GadWU8X}ZSwy;S=7DB>)$KJbt;J<$_m3uv zIk%8v=JM#&LhqHtSj#;SR7RprU$Tim^nY%C^&F2LqO&JnOT1o9o^G#(*Gj^E=2cSS zYw5{gC)XLru5$#(w|b&j0N_f50@6~J3Vu;`mr1}FR6QDuu52E2R(-)J$-F(A9EW_< z_E{J$nr_Rb*b+%pknrOiH#x8Jx-wV&Y1ae3U#wV!6J^su2CF#GhLOoifuq|EaoH-~ zmFytm^dZLE;TaozBEe3wZndqIvBI*(Fc?lbAjq-o%@^#KsW{8w7d)+}*vP5Olg^M! zy&tFh6%4-G*0yJU{>%#Z?FY8vSRG?^AD6#R zC7_JfL<#~W;1ot{XU}p@D1MCqxd18XsdN%3dZZg{onTv*b;RjZ4j$!# zt8<)sg2Q%}4e9d^F??j0}F11|9j@IY@WdXp@g07?vdq0C*x|bP~(!MTk zH(BD1C~yI_=DGb>r%&Qi}QuCYG2XeL1|m;^t8D zymaJlt3m2A(sj72;tCkR)vt{3@3lKdye^{Dg4N7*!>jlbUV3+YHu&vR$B}n7&KaNc zN?tn|Eivq6oXrfB24DLH`=kxXy&;wajkNhOU1AgUU5(2N*GZ*;*kE4j zL3B}XCjetfd?wav#~Si#AeBn#h$SAnOUB^&6hlQrvEmb}lw`B=An0X};Xtc%oGC+d z2eOQlWjYpgEG8FNrZB!0+2ogSX%DrRgC3*l;Iok7^WkODFC~^CdWhAj|DQ4~LH~ew z^KN0H)*Wa-+3bFeXjfr59sJVfa&v|vDK@_C_E6^QR;b z$ihll!et9*EQB#A`LWh0p(c7s8ebHT1ZKI^8r^CISt4ZLwT=J=5Sy}1?ed|;E^~KleK(*4%Hey?rLw1wpYY7A+)bcFIP#}<-Qy)JIv)C>W{Qm z{A$}C&DW_2?&eIH)T%f*onPFOmPNIJi~5)Y=~=}8R}t|oDU{6IpxNsM_hF5>;H27K z?U(AYX|5Yq#ef`kk3Sg$I~pTd2Ty5a$7CQ6*OTI*s7V#kCqnbgT2N{X!J_>yaEZzb zu{twka@gcN`N>%LTZ+h*4NRruWY8B)NliJ`+Q`xMS(|#m83z{5rypdqH@0 z<~6sE+QyfMxG$y0PMIu$#w4Mm5G+~-p|q6b(8tXivkRJ%AkR>vA%D9EUL=$w{JQfg zy}F4yK70ChKNoV+*^vY0L0x@_g#249CeJ zLBmQZ*%J6=r}6s(jge9%b7zF-?Y7F#Kw7e}hG6C!`m9D<4ZgBxkV1i(BqwxXkt4o{bbpe`E?d6Qz?Wxn-DkYiAJ(rOvXEDN?=MbND%dLzxhhS8fT#iOy4Cn+YuCVWnS%s|JVy`=cCs{KeKVs*tG#7n)%e)@S zZ;aqXfdFoCIHG50M=&-bSfTyjDlXh`^`DfVRf#jH8hxVjn>&o7F9?5DQhD&W0b%iC z4|TJjR2UzQm=)4AFHH?(uH&x8-d+KGAM9g|>bvR$JHKB$S!z^#X3D>-gsD}&*++B{ zGXs^+#G7VhmzmsfZ~+{BExT>%^Z*9c^0ets|6KJ40TaDl35rqI39F53~JMdy6BZ@s!&Z79Q+zAhmHe!a%W?aDi}b@>)TsnH+4uc`fQ_4;DK8+nKo zz%^H_I05y^mKFR2r-wp{Xd289APRy(c?Dd1z|{I%G4e1#4G z!eLU#{DZg_D-Rt}1AeQXv+}BUM!N7!IJ_Qe0e-%cCx^i8Gzm3*nbHCII(cUu+WOzr zVoi8m2;E}Pm`>+H(WFN2-qkg!M}wzvc9v_m08@xH6we;j?>^stM#onTMM_K$*&w|l z;cq9~yr;|v4s44M1D&X;MQWm8(1V`0yY3_hohc^A3m~vxt$v50YZ#v+;Ya6mZoI~X@;zhy6NQi*JhcWA~kZL+tEq7*TlZXdrpRXQbhS>aJYIt$I z=$m+^orDFzUUr`{STlKA!tL#I%*=<#pq&p>+?3IvA8)G*AVmDcos5y3Rj)Gz|4QFe zbB$%r>YTGOj6O!&44n5kV9>9F28jt~+z~GoBSmazhOjt9Ht7bht+Q+45NJv4^C#nX zIf)FC+WW=Szx}5TpA1JBRirs#C^g%m-LHIuStNu!QXeWtS75|y&el?E<0wE0e`Rvk zf8xeZ@dks1VcDUU@9wggqlr$lOSY>S0v}l@JQm+TB|Sl!PeAkEdu0szf-@f|YV#tQ z2z2=J%@-$?RLnf3XM+Sv-4s}rp8Ax|6ro4lscBxL=R_1#O&8ubS8x~E2ff|L#gGbJ zE;AJ~5>kDIyDtD2ooF-Rnn#*U5uP~2A_++DZ?sNky17Bug@whV;k z1sAJ5?IBw&$P+?9Xza|rS@oq%T z7p19fEW?cRSzs@@K(ub0s?AQ)j0WM2$}&1>S9*;2_VA7|e#8-A&Wpo-ZU{>*RS}!L zx?w>yRu*Y$EDoG_t1s4(Y2qDTy{k6Ns@cGs@Yzfb!%1I%x^7y70>7N!-C?OYal=!y$(jb=I`4HF#*)(X6R zdNje1xjU~I&y*N}QuIK82LZ^J%Z@hShX)|OLf4YGevaR`$w?5Zc&(M8X0-}_i9HQJ zQgu2npR!1kBIIyzCHmR54V$1!TX?9KZK>v&`@l#--z0~4XTi+*IZI6Q1@&YF8=TXC z)?2zei?z88qeu8XrVFs#AN1Yf1i>C;(TenuDIM(8oMhK6fjz$7eW`wH!92jp+Ov!m z((w{xg{6?=AQ|>!c_2A_l&R54JoBRw=+ow0pQ0oHJ|GpxEEHmyVEg$!Jc#C?b_KS{ zxG#mT9Ve+|$N)|7TTauBg|dPBg;pDA{kTiD@^@vNaZlX8!=Vx0#Rt9e(HThEGH|}S zbUzQg;gKdB^9CjHMd|hJ=$f&1aWpc92mF}oz@nAL#hu72fOW^HWTLkwgmz@a7<|S-E zDq=P%9{*AjEXeqS+u_j%?0^nnq? zT7*k1`~&Tl8e`IYo}O8$qg}B`C>T6LC0r&?q-fqiPmli^h2)#Z3-cikl`w6hXU#kB ze7XAT093nHe^(ob{@l^iCND}O?5DyjhuhZE{$^CuYo8wOl7#*red;`4fg$u^x$CXb zh-UTib7Ef1PS4ceVScdwbUj$*$HI|Su!uIbz^iJF>ns3V$Y4r8#3>Y(`G_NPTl!oc zh*sz-P6oSLEVt*Vxd}(Z;C*Q@QoS$iS&RC)AfiLM+j_Y6Y=o`*^xnNcgi|iTQuw$u zUGLBobEowuB_IHDO(K~@phBiq>~ZAN$w#J0s6s`trIu_c8vk#oF)U$BWi*lZDBXM* zMc?__Lz4tZ{sej5iwcVH<6eK2{2Fbb8ba*Eh0wpaj^Q7Io4!^T>E@5+f&X-s)eZ59fxd(w#FGg82C#CZCMC3yg>1n=o2S@@P$aV zskyO?l%rHsqinu3?cUvH+gaY))I9@T4DA#V8A)*HF;pnUkP6z4)!!~mP?NYa3gwAG zbG1Emo1nz3_qe@#YsxR>JC?0J4CyPZ^)wOPi6WguI#abPY_VY0p??CXDszqxxGNx% zL>t<+{Ma3wmo^YN8-`1)+mFPO4@LObK|=9*?Dnqvw(=C10Yu7%F_!n^(nyf?00Sh7 zVB>VtDCt@fV03S!FgtvA;RAh4vn@ItX@`MYDbpBYkfA-0iL@#Kw-km4^>=_ig0U>l zZ|(5>Hr#f2k+VPl(v-j=%m$JR0?jwIVO^Yb|hko7ZQ>MOrHWB=6i9W2%c4N#1+xSOwBv zf6YKd^8w$Pzvh@0B)q`~LD2w4{qT=bi}|pYmVZifz%X3CC)EK8m$zG($gV)WH!?XX z1Es*I?1xxRbNt!cyV>C2FHbVLggJMtQ%Dj7@q~g~{6?-z~im6$r7pgM;?A zgA9)@thSst7-W;#I;0z_KB;O}8pToQF2I6@Nq*ke`(D$^tojru;^fI@t=AWXV5!!W zK6#?)TT4xIx@-t6IX{3zCux1Ea~YL#Um*9BKZ&`0#-GqqRV;4B9Eb~QRKzHk;vxIS z>*Wt*>tGdZhYJKp3+tyG*t`1n#_|Ir~^8nZ-V9wNhGp?9iRD>zfLVL%x^&Rqi(dCxC(u;mDh=&|UZJQli#l0Ln$L@S1f1Ed?DLMG?rFe4n znC01$nfXw3_*~K`gtr|1`X7cMZ*;f-4_3McTpRE6B5jnc0(a~Dd^{Lmtom+CTPMl> zC!sFTw?P@XmY&gY>Q)YSBr8(n+(+JE2+U zrDAAHedxIW2{yeKRz+#@P@Xf{ApET`?h}viHn!_5X@I@nx{WEW>>q{47bVI=@!9C1 zna(320N3~aTU87dh30AD!bZETwRWBQGv;&-%_v(Yh4_co!~--3yMg)nl-}sanum}e zPE_NW`Ef{*!p1Zqw2`}^z&T-CI@t1aYF%eVw(8za9~7%6q1;(F@c>sk$58oPnIcK~ zhT?zgmp>MZloI6U5f zdfI{u$mz!Bf{K!b`TWWq1bC(r{d~pinjd`{<4Rqh4XW9hsp~JRGD%ir^@Qe|i4dn+ zsJ#iVL~CnKWte?1slJkIkHRw%-_4-VVTud|m-|BwP`-Uykv8~dERq~l?z+z)b|GT^ zo2flRIeOv+QQw;i~wZj$+&b69!{% zn{BFh;={FmXX*!WJ#aLDR0LJ1dCXe%+cm7VJ+N5LhxPa@U-B*bVqlkpH_GR`TbQHW zf-GZWE@0G3JNwoU(*(OoHiV6--e#cKdUJ|R59U>at{|i13xl_{!2ktn>g1&;c6_?E z{ziWFok4FSKDjbFVqkCJ%Ar(fl?JM0l^*q7fgf_HV;Ox6OFuX)Kw46 z=Rb=Ww9Xk($!FLZZY4I1tLzh3BE#H*=7hImHdFTZ2SEg)JES*!Ji^sY3XNTIj^gT^1d>K(tf@=2|xv%VjH3^5==h>+ojJ z`p)>rQVnjKW$pk1k)h5I1oHa%VQ?BqGg3+LIq{boGsn}Nqw={)6Azq^|HQ#YfCL!3 zXnW?1xj>$*d!r8!5U!FTwLcebPGD!dffogA(7&EaRqIOUe5PqE6N4|Wt_#?Dl{fwE zZfHRSgRq!ePvIB%F84~^D9=OnHWq-y1U6gsa;JaUmHS__jMrapC+aF7wxh%z~k+tD>=Bd z6uw;LJIS@$ih9qn#agtD`1YsgYfi2$wuw{&W;2c^kaeGC=83+pe*zZq(<_=?TU@CG zlfJPi7b5-b^oMcZ=}yct&!0X1drm}KUSJHCRjHi3{0*4;gI<1uGlu7{aabJ9T)%7tZt zt}34&SlBbYiQ0Ppxw>L&Di5Tk(a`hA-8D62tP4!&48I_^IltK|(9TeX!E<8Bk$cq# z$5@r!zKJ(JiKVC*ji94$4FkW!8 z;>nJ=RvCOS!CV9Pl;H7ZKNscBMh>O!sjCJ3-QMXS(S4@p_*)uj3J8Oj~!4dL{ z4_wKCMjBfHiMT52+jz3&HyV)!Sed0%ijdaZuWgG^zJ^F^6^Z%jMCzChzVmR=D7wdr zCn@V>N5(tv&`F311#;k%RmucK9-sQnQ~Z5pc27R@*X|I{YQ*f{wAncI2=)4Dlstg;%7?!y=$>6 zUS+$x%2*H)I3ky7| zJT;mI)!B_a>4x|A1}(w0skQGC)_@HLQfSw))dk=6kB6ulmjga731zsU?q~PmFJEr} z@h@=C*2WD|mZ}64^i_8h;hy@9o7{t5c|E-a41E}pIXRxnB()kNFd7O{H|4X(C?{M+)Sn|<4J)b8LZRncvzJkd@J8eHng#Ku!Rp5);GJsn_W1!l z6J6)i{gU^kDo`$W+4LER$QhB)@~Cy&z+@}tBL!MmzPU(= zG8z$&jbb7>ru_?DSt+_AbXbbEir+wbo{e@oh?D~f4Sokd_^O_ws_nC;)@UPe7yD2y zRdE!H15g7I1ebYQ2_*Y8cAE}RN7%iEnhV&~G^t7g8QADKV&HFfTtK-u|*6e64rF!FW@s>|yV`?x_sWkH-9k2BvH`}F6 zuh3;asxvNWDU12^e^`Z+4QfMC%@qc?6H8)x`3tm3poMhw_$GR|8N7dK2*)*gl>{z= z`qBRL@l9-q-)@D!0Ul&8G%$LkK(%yXcZKL=U@fJ5@{Jv~s(i>Fg+%g=qB(tiW51y{ zYA#SOi6#)Z`X6`t4iuMQzK{9X@0UZvUnmHw3wBej;GOp8Er|OJp2pI}_R^m%GZ|CW zl##i)#{URr&Agdxtk#g+CZ?P;^aXjm0^e7rTdYOdniXony%vmJN zo`d|PScfP4*afMBO66Mj1LydzQ2C`%APfwHb))3Vu67H{ffz! z`AH}cDN{5sGm`r6BE!QwXfao|e}Gxs{eg)+;p0cgWetiE!EqCaFEbIxJaR!mh=&+X zIQ?6tU0g?`G$yT`?jY2V>p5}Ub+#rZ7L7L%cdyfGi})8x*xX*5R_E})66L>eiq$q~gD42*}xs>YpM761Q}WOq6r~6$3&41;i)R6>W^&z>0D!@w=A3kx;CQYXji$ZZ_qqUi!EAtW^9@tGs4EuY>D;NAeemO*Y#ZHJSI}^UB z2tv%%qcUMgc!ySg2E@R%EJ`AxI50{jcqOpy4^GjtHLx(n`S-WukS5eGHZH7Mm8r=q22hOu30(o z$*O0jv%0EhDlG)yu2KEeda(ep;mx+f%+PXvebPskM zPlOCO-NoM$KiGgU{niJOJ0@gb zWo^&pxhYpi>hW0uWlvT}J9`}M)>gXw+$Pcoi7rfJJpIe{nw zRm&zR7_vv(EMvO&_$GpxzBM%SuM;LRswPS>(d-R&U#Oh%4^^1elFB863GQv39I?L_>V1X(LP^(fOM1Jb+TP^~b@}3Q_?MyTHo=9GjBVUx*W%W!<(#I~ z4Oe`PFWKbaLt>QS)9|l$rq*g*MAK$!nB)^_riJqmSQt9{mh{0LqF^L=6Ti!pj=}9- zsHbfnvFrq%q{AZCL#57G*<}7!t3GE&yMv2Tlkv!oc)cxDpdx}GOE%?2dZM`!bX@e9 z$r@GL72pV4$Gel)8v8R2=O}svIFYiC3T#Bb@GxebTnO&!R3EG@nT)&c3Fe-i3$@Ul zJQ&C4gl=ySc{MK+kLvJk>cWv?qFBJ~du8I>Egs|a2mh>BJHENhgi~tA-90)yLcM3L@t45cPfD> z$}%6DwXz$ERu%94`VIb=pMx>-yAwd|o<@AUsODyX7jlmZk7aGGFZH};&dnZz4gpaN zLb$O+XfSZwQtK8@=wMS?!xII1k+eR_QY0W6g$NdZlg6hN;Y6_y@NyOSU1cm)GhLF% zX0JRePlYPA6Um}P&+)FbKlk^)%EC8!PDBvA#bDyJsQ}Gt{`vA0I})kHqxb85XOUX> z2Ih5Ahmc_v#>I&A$w*<&uMejS`swi8CTJ!y+m?VmmA_O+a`3t9_b%fo^k!czIBpP1 za_(0+ArUa;idWa`c|-WD2R@7j-El*x%yFWFAr|VFqpvc$QDj2{iq`2PB{p;UkF=}Lp@?hea;r>L?!!w3e0KsPdX=QE02r%p!;f{?+xY*OGbD{ncE zXIS&u59T8#KkLo*0mSD8Vio)X{}7bZ<;@qLvu^j6e>*1^bPbE9=y;h zC76fm^}+)p7bHJ?KygT~2D@i*aix6pPlWW>d)SnYcRMOKOfWPF7Kwrq(0mEzA&AAN#PKlBP>y9I*X!_g80e9D#$jSlIcXXM#Zz_td zB(aH4j_JeYVq)~yks@;~mk$#wU99xy-kNd`DPtD1sS2}CNUORj1F|CCWW^ctdUJ;K zshw;lb6E6Pkv_F1s;0$;|OX&4l2wL(8S~;KyY)v&(ZV>7rT>J z+2v;aAE>N0JF(AHuATk`4*wrv?;KWH*u@P`HJOv$R1+rKnruzBZM&(-oNU`Q*-hrj zwr%^{J>qI`Qri+zW*3%PSgJi3AmfKGn1r%Thom&vwqvI(BW4WpMzSec-M{Ayb&UTk%auR8 zSgiFNzNc@&$+#If5pl6ti~lD765yF=cmVoWhv4^6Yu^;Ohv(|X;ryaa^A24+v2liw zGL-Uo^%L<;25&3VJM*`%@eXgP97kV_TJdxP8;EkEiPMiQ!RhogE23b3G&ifr5vD?L zb2vv=f=0>h2z@2BI8MUssGfw<^$TI3<5%k^z7hY(V>c?AAc8bG zhmqp0AsGmq??#DKESQ2JTh1p7oabXvhe9Ex4m*Rywbys*QkK>2Fqf4n_x7xuIZA%H zB_D_?040|LNw*|qDoqxRV)}K)Dv^gX$WiENvR>j-<&#mR&O>DKl91b7#};zVRf!zL zxYeEQLf8E;U4T1INJpl6PLGoYk2)UXh(Gs5t4l*0wXuD_c zGGv<7B_&ji=I#Z&)!DTVug!)(tUmwPTgCbXN0xb;x^27Azr?D$y;1K)`sN${YiyRHpgI0YDDfuxzKy@7kQ@t~so?UAUqM#&Q@8*j0*K^JMVs(IIeLoL zmNcMPyg|$RD=ny7L#fZ7*8Z6M6AFugL_vqFxw1=rt`Zp+lx7DOCmbgrgNuF5A;~VC z4Oc&Yee}BJ>UenJy~{rUL*&z^Jzx@7bug{*#3S#xM8|>W*9Yy$e4^C0K$#=PR)thk z;Zg%n5{=M!;X4aYtaZMW=9~5J=8XsCElsmeAt!JpL-!+X6g4lq`)VSS6tOgZbyM6} zyOJope~Xde-{aYuvEy(gCu2Cz3v9a(kzLHFb!8Ykc8jkmR}R%3f4}te!8os49mVsU zV%Q3>6}HuR8~;7y+;CAWsp}z~GCcWCyZJjMSYTUjCwXsWzKu?fMl0ZH^?s4X6wVTX z?sKDOyt-rm#E@pnGcTgy-i6tojZd0+)^E@Dj<&h&$E|Vo5}!;-i#6srj27j#Mi<_y zb4lnx=-anvD(#kl39l8@y=Gdy!j(#-j&0#r8@uMt~(|&GM5=r5MzuiZy@BPzl`sVQRu+?7lnCRgi$> zHlH8gy!jJc)l4$@obds~3v_g7q3`d%dKM@ugrFWOHeI>mAMQ!2U|6&X9itxXT};Qp z5tj$#1&5LYN#d2NR-=Zaz&boilRc+fXy~dzKq}mEH_k#t;mfciee82HN;f9ZStSgM zzJbJ8bmck>zG}hfBY#suXA`TM&l>~v>#^vu#5b|AQzhU=#-ULq(4^1=6ssw# z!vg=kTSwWnev6vBlCjk`TV$X-q8S4|u2fh7Q!&B%^(u?B85kRO5*iTJU3hTop%@#- zf$5xFrfS%f5UY4{Ckq12RA^>Jxw`g^jI@S{eh)yw5L@$#k8WFR@Odo5D9h!#Odyy) zdsv#%tKkXLOc&`EJ|?4`$juE1noE3+LFqmdFE%TxV{BD_e?;WskA^ly5ktk?VQ1ks7(`|R?Bbgf(8vwQYj$`8zqHm=IkH4YLMuyS zt>;J**2u2NdI9U>+U?95=+%n3CJm_O9zG)cRUMFdtSh(o51PFCwG@=g`bDW{tFq!{|rn zD=Iv*6CvUC58STrj&PnfY0o5$5lKN`@36bp?9?Wi?J7nZ3j4*`!Z`QT%{V3EH`O_k zdU&|UWM-;J7_vFz1Zl8W)k>3Ce67U~H;7 z#9nnNoQX@E6lB}#S4 zY#wOup0@m8q`Ic&`x@A2m4DEW!f_}1&Nd26vFzKQKd+@PpwH@ZySu(g7kb(n%}y|| zJR%#3Z{24_*|FY8n8?^lAbR8WKXnwxL#6VtB+frQZdOR|jhe!%@wl=fYS0(y>g5QG z{u$OC7`Mwi``Py9fTqP$3s)MAg_qTwZ|%Av)$cCoOcB+`f_N>So&!` zG&1}NEtl<&lNsT*$!XvFW@y_YY4XkVvRa!F&rif-b*?5h*G31^F?tRq)0WqEl#5l3{k+b4O{#P zdUu3>YCP&=s9dE=w1=j5ALuq~)yg@IAI#XKG87Gcqi^z)jDC|;Pc z*ER`x@YcJIftZn$8+a#nZu01s)58^Fa8nXZ~Ti3riapT<Q>W@4sX$hW?p;ejKRf9iOdQQnvbt z3N>!`YhvL(xRCIQi-yfBP-8N`Gz$)J*BC%Zd%~a=0F=QHkvvt@3Q!W{x}j20&2W?n zq{XP4@d-ktd{@tQ0X-5o&zKHAXHD-WRW1BAC#@YQHyydyr6E*@&-(&{*Y{kt9!H-I z5x5jCU`mrsVY5#yt?8KIndu$6zw|k$xh83GnoaG^x_E|?F_#^)HfHkI7XgJ)wns{D zjp?$Q%)VAo>_%(WI?JhByD7H;pT_80=eBvnGqTnaQc;cO&_Jm;l`)QBAJYkG07`+r z$2Oy0m!Z{iLqVz-X&8xZLxt`erkN%Drt}XIbObah1MBr*O70SsI$vc*;|tU^8>b5`x9`mZWozXx!aUk?w22 zwfV)T`WhjWugCmYGqL&kZzwNDWDW=|;$%LM0TIOxG7Ihr(-B*o;}OjlZ5VCShB95q zToW3Jh)-q1!9rBsx z!e{mZYS-6BMqAKph-Kz|ZFOL9L0~k7sCv+^YMN&l1(j$-oYZ^wm)ql64pas8urh-` zM-arr=fjWil)qo7UY)}%{pbKAv%5xVU@@fw{aj-Ul-G$R>McfS zWv1RD%L+~G{9L3hdJ5dEf<@U|XlXrVwkQ14Z-fR1B**f^*)of?fpS9S>Qri8U>@5O<#mtOI4hVfII#9 zql`tt5VE&hC){3L^-#Iz2%y}UDv$~Y4qm@(k}V?R4M}0SWbGvJSG+ zMw#a^uUd-#d|hf}&UM$j{Wfka!pi}HD+4KS^4C8-J+YiS(+t`0Nwco$k+cukFtIH} zWo)(Da$g+39X8eZ_@`_5X^8W$4*|Cen`VU?4(&u95y2lU@>G?~%7`!_Pk0Q1X2>NK zL6Jva?H_ZP*E}J{#7M$MwO(-2)Bs z6>%Sf^&_?Ou%%M4Ju6)pw#}Ame7UtmTZA7{zb>ZsQz{UL`fE$-dIDonOcLi~js`V1JBBLFFzQ z?;;irmfaWITpw7>6ZP=UsR@rpaQRV$1%KGe75?SFF1jo%;UN>_%h=C`1!5@wTM*w3 z7^u+Hk^wDJ;B<}sl^mE-qE7YijoqnINylEKIKLE8XjsHQ9h?mVUMX*Rb01)BKS=@V z`#qq(uUlNij)01Q5(-@|Q?g)@l`U2>)|Ai;nTowLJyuoL&jtFN6@18)sWHiXlasX$ zn#0U;=uXt0U0gqhtc1I{~46DcFkxCS@1|DN58Ty#Gn6x4=AN^pWH@3SHZk$g{Ue9>w{RmSCa( zGm@z0zfJUz{xmQD{1Q&KW7|q%rSG^hp@JylM0La}oyYw0{ajx*!*BN-T|FydOYjqqtB1tWX=r}_Utl7>~D=Knt?QA0BiMeXL>we@3D zCIe4U#4#;Zp^-T-L$$w2@B5JpMQh%a^u$`8@Bw1KeH{O4L;#AQ3Xz9~%9ou}x2;fr zGJKLT@Oci3R_W-9k+QAX+-<%5&PJ`Im^Y1{=vrC|rW*B^rimoH4md^S?PSA*OQ3*a zoBo*_D)Q0Pr(n1 z0nhkNtmeiye8KSy4i*QhD{=zqHHG6iT*ShU zWwPbuwc*ei$E@qO*5gHQx-acgU#*EUyCRBO(Tc$gkIeZ}TSKbkUWV#fAew|PW`;#> zzz4ay;-Opi5WeX#5ZU+y1(_5w-V{$qBvuH@L%2F032&be^V}Y)$V#6`%h?jVdvRq* z5D9=DNBxIup*Fa{2gimxr^{AR` z<^%NlyJsNQvRhuOPdsfn`^DACl9l^Cv6tq3KA6;^?;YkVxVL=ve*aKUZ*xPTm^YSF zjqb%%ZFtj~H@K~=RoGEgMjN*;`E)z`Ukfwr(mJy{qNZQZ8!2tmlSIZXQC(dt)7ds- z@qKY-n{aSNxB(h0zKw9my6g-_e=@BSwn~u?}nKwi>wmhRR zsme_~=4lOD4LCY_{uImT?$a()(R#ME&kd_Z)}hSA#NT1XK-J{pQ@tYwCUaY=o<_DB=XkHwzK5QptEs zvtv`4dlJp|j{?3)Mo^?S9oE8=J!7dA%(^6ruy32%XG3sF$mudV-}K?xtL~Ym1Q^FZ zojiC+lxuIp>ko5JLszLiE>Q(mp3e3M#x&bqyYQ_gT4J5(tBoCY&Zj1nsSav_<(A!! z%uLHqRC4~uvqc?gj|vz@0%?g|{6(Gnzh#o-SqSCIa5?{_i2VjR+5V|jt_@lf_GM2e z7^sZ(7AsC3X@w==7C|iy8cbZ%8YVJ4{U2Tc4xW@O-zZ}(;r5lzjMfR012d@laU8W^ z7*#sN)Pa7Ys!4AF24!ss%7idM4sxLGr%GdOUvyC-)82pFSE<9i&UIlPldd-~?-8bL zT>hCEfj^pB96iFzrce(^hfEIq^qC(8bAzy8A8N@ZEWB`@)K|uyPnrLme2eLb%HN|L z4>Qb@-2Knr?Y1iCHMWhVw=d2wQ92VC@2zRwu(Q+@sm#E356Ge&$77du=fm*(mzkmD zH4*=aj7D3k-Ap2WOxyP! z@O+F!@fZ<$*=Rt9FbT)?^lgXBgHtc3A3O?(H>4@I?vQc(xp`P82=#C*610N2F4?0NHAy*wf|6)VL~IpvNWa{W|B;X#nl^)U&%b;55}Ov8nBt*j(_6ZlT15jzH49^Q*_e9 z5L@{vQ6+|=W(`s_RrTw4T;UD&+}g|^mk1FVuQ9PoC0QBVmRAja)`HMru9na}gQfG} zG%X71N#^89ZBAP^S=!&wsiLpCJ&+7>g>9}Pk9ebx+DQ9CbOmbQD<|Yi=Zr&5zMmA- zc_5(xIo=@^x)UJB|G~RR@Rx$IUY;|VpHr7!{6yJavTpp@mY+T1PUo@TWbfXPRF7rN zhh+cysyCF=;^8UQjx;mX=MB@E=z84P0`ha>vvVK{#>Y_E`q+lru%GJl&9utYi6;Lr zjdRv#Zi?j--WnSXw2|S+ztS}bMt_HMsKYe-Pb%3~#9wI~aC2?UoaIF#hHG*HkXi<-5V`IGcrV=dbO9zU3B@c&;v_>k6G9ZM}za@V2t}SNGs8+Qvy_o&>#Bdzl9y2li{h1|6x88>wlO896$IR z7;dEu-^E0B!o-*(2>p@r-DoJ_)K-TAfA2?b0SkJkf$pY7UrNj>STb7u_||;&H|bF# z%tSIT>D!ynuox98_V*-~%^-q|myWLi)g~V>CZHGvl^o8K)OP30$a=oHLWLT$PpLqS zLw+WQ?ytrqIyvTm7LYW+1*IBUA^$u!-ZwlbpF~$Q2xu-l14y#lL*ipy0nTTh-Ok3mN~NP_l}a58@P+z+&wxi8Z^t*fNhu6Z z{neVp2QcGO8HUWfyYwhVS?3%<3h6qK!{&h8u36C9pIH#jiGRmJ&!-42;~ZTC=X|_bx4Xj}H@Qu#AL zC-Lo7Is#7yd@}Llj&85>vzN0b+bD=m_Kv0>KEe**3thiI-QQ{NVN@A7R;~RFjjYjT zokXWiW&cfZf#1^ByUtnBTkjQr6Myl^*=B@xLWB|PTWT3_Y8I+aHI;`Jh6PK32hf@eEc1kW7TI4 zr8BrMjSk{XtFr)lrWk@~YgQRKVVi9G(fn+>?e8(U{wg$+i`{3iRD{Y`cmH)%#Ny#} zCAbme>-nIP(S`W__VG5*xAzgR%Qf7>j-8?YzE{}qcf*w99imgR^t;WA+!qJTq3mZa zo1=w+G^z2S=X>l;jfK5oxmyW^!;+=grNN|1-LS{{Rlqf;O1+1SO1mp5y0&i}ow*_W z+yI$L1kj<}8rfsKDhZs}v+T51QD|sAb(!pN=SB+qCeGmUJ%~o?dzQ!|u0hJ}^9@`fhUF~(NhRdB~ zunq%>HP16Pt-0dnG3JR-nqk{7Wyqv(+)2^_qQvA|kG4Z}GB?^e>0*C0n^$f@uB62( zD8>X3xA5i3=2%0!?*5%ph1r$P%shbSuc5=pJ}Blee8s?;AV{N9Mdf;d9d~|Q|>0+LJM2+oMor&+^k7;U4F0fLl-PGwO^N#I4&|+}(CMPPcdA`wi z>A2|OH4%QSWv&O~6J(~0=Y;$vT9J>O@Hz^D2Z2ZXCNL^hYK1+QT(li2Lnk`t0;H}Q z(vn@U=N%3^{dhHOLZ%nI(1j`Qz`MTd=L3wB;8 zRW1&jRpaya!$tH&H^n_`x1w)tF7N~$#iIlR|6eHa|H21-Wds8^q9-7F6 zuHk*Ec79!Q|Iv^)j6C?M2Ff3XWLP}*t7lUB=@$9=T;f9p%Z35P{UO9Q77lzwl*K|M z94w&UW{e&oWu4R&->2?yDYStvDnsk=XJw2(g`Z9%Jy>8ZksqNQ4;^Gi3*&3ji@^Ke z6DbtL0V}Kl6^8P|{&9W4T~n!j@k+;M zeLDHkuG=UJ5l7mI?iMAd`dqD#`3I$G(i@}eSYVYnm zw4w;PF#sV|`6n?s>R+rO*KDqjjCgowU`MevdS8GCU{dqJv2e8rwOzw;$orAhZ>9(o zSV3n|+J6n@zEoTnSU-0y6Bqu+vSyYi_eHgV-wsgFM}L7u+wTnKv>_7*cpom*IO<#+ zhRi?4kOl+BBlXpuVtD{$B{hwO-dRgwP^y?p-4H!l;g;anDHr;4JpDIaip#_kXXGQ; zT{?*7Tx5?;fCV7vj>j6W;VY~UykyqPf8V}zV2n+P*Hoao?y}CQy zYtB8n5yfYsfT5HL=4Kym`MuFl*H8s~eyWRluxtT7kLNk}iev(fPIm-0efHB6xCE}OZYm@JH-^rit)sf(&H74cYX>W zsXqajfG-aCmUnidux3X$CTeM#_%Cm^f=~!K1+C!dAUBR5qKY1q3BieqPm_n6iN%%H zrnhUBE9#Cg9Kll!NFOVKdfW7vGQy$hvu~}W1J+L$hRp_3uE)POu{zI&rt`QURvb!L z(Un(92wd;m?Fru-%fob``WM`cSL<&Hfrg ztr1>@pk7^0JJ@b6maf&B)+rH4fN&%}$vWg3_pN|`1~^iz`ZRZiR(IMXz2+$O)!8uX z=~|eOaOWn08h~3XSOPK`5K(i03W%7JZ{#1Bh6eYkfM_)nN9tVeXH$`FM!JeYATGNq zMv&%rBb+9~lEf*6FBe@b{pW;ZxtyeKd%Y-6F6DAEMOHRCoCAjeDiJvIp*ne#5Tf-bcSW-FLqqwX%j1PhQKd|xXTuWfek7@`w7`DYR}QO4B~@1En?LvfK{Y`p z1Vi$Y#YSojFfClft-hpd+x*_49-KEBlAcej!_TR*`UvTret+atYA(yhMxV(MNjJ7s zv*viy{#eVSF1X`Tn>;eS|1KDPAVDjT6Y`K%>(2LUrsgmE?XGw7$tSfnib~FP#_ZXt8$Bl!rB?vy$(D zJ-J>xNxsCTqRwrLiI6yw|B=`58DqmzNuDCI)XuhhE7IgQ05)G_`feBY z>rY${d{q39_8}ro=BhWb=feq}a#*P%d@!;jE zz|2qy)+y>UW7*i;9sBsq!6k75Q-jT_r&?RZ=Rb2Ypy=DOQb(oLS;>acFM=Z3D>+*y z9e%DnDoSd}{9ZKXno@N#;|?K?MzU}6lc`mX%|z;1ug^ZE@!OgIx96&_ogQoJzn-gw zOhxDbV?FW5-`lV`FGX^{6`{g@(fKi(GMP`E>j;v`J0S$BI|@#jA^B0xqez%a*m@TS}wV?~rQ zmD}YZnRJEGyJO2-hBv@G>$7BG<6dX78H`F`m05`k!Yq?kL}QF7Xk?EZe|V6JRmw-d zGIsLcEY{st9?I`izLN-MrJDO;0x7{NRCs%U2PGr+38xX=jAYz^VEPHsNzCo&95KC zJ4#=SqzC|!^xW0!O8gc4>iFUHgNLWVX_Z5jdlX7B;2Q-1&kkZW&jm9UNotuMjX9Bm z{9CE8<2zJ1a7sSl490)7BKKWTNiwr{F1V0Ra`JPNpdafT{cxMNpb~Eibq>x7!wGWxmgUUFB@{y@`LuK4dl0DP$0jMSQ+2?q+=dqRoieaV}I z5zQMdrj(Rf0+nYK>=)aG*P>wTddM@(|Mnl_Q(eoRL?=lsAZuZ>MhcvgXsC%~0qD6i4rO0tvhbvp!*`6s2am>cX+FeDYOkpLzQrdF zNgyEs$cy^kfGUx4%<^+@pUReasi;T;$H>aZGE1w3fG~lhf8TF1?K3m4*_dnNTyrun ztmrCn`Uah;`hDAi285_L#Z1KaPUbDuTdnB_@@#WOLQT!!x$besYNH$bHB)D(Ga19n zpxLU8#**-(WCg1(3+$sQl5bufZIyL6&=k1}BSDk+Mr~utfH={7(6JY^`i~`5Z|AFFaxet$r>>?SMt!ucig6G8GzR z$JsF8wV%UaR*_RI2-oMfk0k-XTreI`84n~vWd!8lTCuE+2esuUyAJPagC2Nk)|_xI z_Md2ZG2Te02d<}AirkIoWx89CjZQXTz*%s#p07W5lHtlr=>IHWD9kiC&9xmmV2el+ zg*J$I%S2Y8H^JSs@+Lz?hRh!SO7>Htoe|#s`xL3ESOGN{SfMY32h-2L_BPxpkmD?U zWTp@+LOfFCVk2!$f%lF5Q&%-5JPHG$me2ElZ+Z@mf~<^x(DTRt;@ielAN~pjO6h~B zcZd}&aFjVpe)CS`=*Tq-eKcVt%7D*V?_FfE>l~_yPO9EbNCLP%V;ei0ug5A-aOa*W zk8^t6te@am*6JNQ<>34G_0Zu&Kr5lY6v3WW0M-~?5)v-&V~CYxK`BT-l`O$-P7V}v z%LEz9$f&yWqQ)s!tU^O&R$gi$;<-!t;i2`60m82v*y$E9)a7A09&c}w}8ag0Gb;J4G*KPEsnK3-Mom#!x z0eZlISz*>pc$^~BbgFC54MVxFIDG#?3|_tA^lOshKjt=g2nuO^Gid%90hb$mRJA)U|951fq(ZL>{pr&jK^U5bfOk{8kD=%t#FF9cX1;HM{ zMFJK5e%SUVYbF;nBv6Bgvd7uk+y4odhT%4?q*7S3(q#86R{<75h0>Pju_z;{m`<2g zYD_LE87t@32>@bGwaAoOc;?K568bHnse>+iRQVEUeUWnSSMTU?PI z9vy;;*I{utqp70R0YOWx8(59_E;72Zt!qu^AszPIT+%lEy+dpeHI4CcA+WU?+2f~= z&ePuHGZ7*YYj}|k^5xGwL<@S1Qh<;M-ea_xbBSH%?@2oc?H7o7akc=Sy+$ojOB*ah zF4IIgy`>g2T!geSf5=)Kjdyy!^d}nXag$Hk|HYwBX)kQ&^csVBXz#~*7$$H^g#up$ zvifh+G+6#QUoS;RE`I-JQZkvZMZu@+X}Vp?m*D#ou{dE!OHN!!_W_tk)~*x0W;IZD z<&q79&4k(%1LlYLdKK&Az0{eXL(crB8(WL$il38ziF3>4fZ~e`)4A6p>cBpw5*3DhO$}$ocp)bS#&Fx6>9pj8WI`<7<@?s= zrb1*MZE86ajqs2(HOB}QsNone=*;p4z$q`u+uYt+Lu$l~v~txI&>+$SlEUmzoxh{G zs=W*Pe>2=mzT#xE%+;8*lFq-CTi+h@r&B66e4^g646TRbYv=T`@G_?j-r22)<87j3mn{oY4 zj?=?gb8YOfoWoLo%lbyHTDrtc8Q_*t+!G7H)>-}#=++~*S{Xc#Zj(OlRyUr~pR|S#EYb5oJblzqTALNb`XT1J4>*>l2yb< ziZP!Gg*1xWPuN9PPAx>y+4Wvu5#vaQm}1oOYRr~)A>EpP&;L$8FPYLYx;hM0z`6fYS&%#7brShj`PDHHM~7m1vmq;z!9*8A=Du%pq@ds zLQNSgx1hX2auRn>G9D-b0Fh7>fKG?s3jM+xsX>1C%twS|&vR$wY?s)_{Lw{yAwO6g z05dtp6za4iX2rznMv`;Y#Z1@xM6D(J8D2{~{J|hg0-}ZBA@}z8Bi$!I@1cworUvcH z@CwQ>*juJ5yBDUJvl%A(6L5B1C-VsMT^>{0gR=!P?mP5JF5RUD zEE2lbcz#k(lhJQawJAKc2UPc?9%=8EcHFDV(7dDm;~mE1Z|x^)_vCV)(+y^Kk{+4Z z?g5wEub7d}jn?+(g?4YU_vh%KthKaWJZRLKCL1}tfy!pX6z?|9pI8xj^}&bh{@~|y zRkgQit0(W5mTa`xV!Z`2qsf0WJO9$+XF(!_2CK8^Jj#f!Wm(F94P#`E_<8E-)GM+8}-QLA&w9&>^PPX9*w#7z{Tpl*6ky#mcGeJG4Jq-dV(Xh(Dj z1l0U~A4$BNVlz?_Z+}}Sq$e?QxXSC`KcLGZ2U!u-7Ay5jzr9&Ojng~@+f>n;YPkB2 z(&gk#$mjWB1<4S}1-!9$@Y>f-JSuH%5&e6W8`m>CbwWDlkqaWLs%r1AVLdKK55lBAd(8*W*)b@W;l<`0yTCRs$GH5SR7c1Y^Ybk z&1dg93-2p`bjz)yWhf6{E^-D6{@5m$dDy=qbMd;wVSjtYitLA_Fg4ZE(hd!6?#^6o zwX=806&jG8gZbuj>H_*n(27kd*0{cK#9hPB%tqo>aI(8DiLrRq$hY zb4B(*0ky-wQ*Y~jy*ka3*_PTD{cLBq#{GigI}qWSeUmrcL#v>@3_5C`XVBE$!^i1bYNNutu)cU0}+aOl?r z+_o(pOwsg2tI8c-yBHl;xMN$5(9;VQJ3sIu`r4bwwrg#zm+FWqIYNqck!sz0xaO)f zdm3o7F7^ZA13p6o&OdW!WCa+7i0&T->OI2lwbrlrfMpnWDI7jHv`R$fyk3Drysn?& zgH!7A{>-t>V4 z&`dd6P?jUxq;C1XsWT}qWV508OWZ3_)mC~T#?R%)++Oje6uE_)G~_S0mYcb+Nwux> zwRHU%Hrph2kTvU zXb7Tq$>3!lS(+73@*d?V*h66J3!Ar3U>Eu3g9TFv?=6O<%UbVy40Oppf|(R5m_PDgB2w~A)+?1h+nEDSYF$ug3@Qb(=>vNx!tc~S!KRm235{ya z22ibapKy6z(k4J+5=TR`G`xy&1No4=zj3<=kjP*R-o}Dh`~1jCOBO zf_&evzruCBHSVnh8-7UW{m&h>LAwE&M|ylM+Y6=n^gyk;7N@^< zB)!XrQCaRTClYifLR*DcIJMu`(JJpR*08D^lc?hGCZ8Xju5q_&KP71hJK^+n!~QNQ z0*fGv9REc}iub$wcj{SST1$Oz7N-~-`-8=tTF3Ca(#ZUSg@oJ+6KV)&Lqgt~-OoP*K?C_r!7Eg-3Pk)s(7}vr5QX zn11(vk3q(K@c1#~is9j9speKtZuAfHBb5vOpGd4>&fF;}{wKKCLNcbq={}wv)mdgl zBYU4oz09bifv0*Q*tqPf?*Es>T3cP8DiUC5tKF ztI9l{?_ZU^5Ab>)am2!hbOQwsUGMnwy<|adHSg>fltdji)#&#?@~iJ$4=Oz~1udUJ z=|lMvou2j^Hb%rJiAvq-l`R_SyZGw-V%B~^{A>&gb5B>Xr5N~iT|x` z1O!EhsRGduv(~y?GQf+D)Q}_yMt@=GUNPWaQ)>WtBBN}$R9HU^zW}m@GLdd4*0-bY zMLBq2sgc@#JtS{`6e>&-0Wi|ahI(B@S@gy3snjI_eP6(vQUTO*VPl12yHXIOg zis;5<$|?W|oy;)W#8A+P(yB0vYJS9o*fKab)2EZ@opf~1qGm9l(HA|J){=Dgf<>zc z{-9;MYm~(h6M*O=77qMSBG%G0rh{1-+7~hBj)86gNDb3IYoJ`{Q(?wL!X=H$9C@x* zBBz4{@4JkNMsK$M=y8h%_)erRlrCrUjV-}n0jdC93h-8sG2$W|ICDjal8WZlELh9H z8x^zS$`7{83&sZl#$iheT2L+^2pjy^^Y2y7L%P(+fBdx)i^Av&m;}mD!BRg5IJ|jC zm)xT%3;E~*-){iucdY&nH0F)wCV=uFnd=At7z+xu>*!x+Jdj_vrvohAA1ofqtdL+| zn1MLOUL#tsTLbam%+^&o74y-jq*{tMVVucOn5@!gn_DgdSktJf%KJ|@_LF9}TvvN< zpyL2Ga5!}Ae~Xb5V*S-VlU})Kir5$3CscT4D1u6mp2$9@#L{*5jz-A&kSzunfGNNb z4h`T+sLh3Q{|>$H18f>LfIm_h-r350=6G|8|j%!Xb5Hcd{*bGibJx5g?By`^+!-J!9_9tRy zxpaVE(0JdXZEMX-B&75kqUP{sM9;@1wI=Bw=6-^&ehtQ5{}sX4chvN`f|d8H!e{Miy8}26S+*A4uR&4X z3eEz~*{wE6(713xm5k*t<`At7@3OT5M0B0r7Ba}XAsP}~3m%;<4iRnj;kCs?QRn>f z(?Z4d!)Ve@kf^J_L&=(HJ+wrE)X1jdVl6#jbP6ilKCBoQ>7Owi4^vvz8?IQi&wVpJ zxyi0ip*!vA=y&CJXTrEcnqL$ejGGgUYhEv@Lz=IpWJ~t%9dAxGvGLJ_q@@w=t;JpG zoYHq2$(V82N1I=c?3vYDSYxh-{%|eYuQNP%95?fj2PG#{H$R4+bL@V)!Iv#h8+l)K zgJfi6M8LJjs^wc2OSQB*GM{VbNlB|}PESt8HZXv)KW(p7e|yv-B;@xeW@PNuvPVO1 z?+l+=v96mrrFrPQ)M9t~<(T$k-fm#~{Bjvbbxt1&uc#k|`B4niEE(o_$GqQyUFp03 zwV}JC=mPyg&zukig9}kekiShMw{4hz&9Z<>#d7Z% z{~Zb;q3nHikXeCK7(l-(ydFuZwYhXagazRMPxexq@>!a0^j z)RPXVk@mD;+Y`yeBaDKDd^Z8hHm$MU^d411N|JL=EV164XoOc|@TOWkZySgQ`4pS_ zY?MgQ*OZN!oq295lE|2+*VO05NRS#|Q%n1J@aB-7@Av)qVs!fG-+X;$+;T^JZEF*# zKC&?p<^8Q8W6;sCbt9=IY21|FoC2nJV{jV*dxQV~7mBT{w>AT~S zdZY%fXM0I9oeoF;7h`W3R973c=>|^-1h-(p-Q696ySux)6Wj?9T!RO9cXubayE_}$ z$XR*6nW{5Y=TyyaYQtjfN4l@R`|f!vafGkIwqbQIgR{oSW&Rue7aicM`|Isi#r&oB ziQ>sx3nI~$VI9f5+J%r7)DUDcp0u=ZD6|R4^ftPMnOpLHHzjylX9IdCe_6=%MUB4X z8)%qQWAc0-J%Cz1iv>o0i1qM$G2swWr!SDmg~-|9a5U|sqJ5{1MFG_hDTV4jv093) zHqzbr)vUB^YTTIe(p^4>OW4QuB8ckGC!9g;K6#9&*?CqFns@2++V@}ej)Bn7&XRdc z2kXp6;tE_ddUoFRL{cG+)?=y*GFmQo)BXs?aR8++XtIYl5Hax+**5OXb%}rty`l0$cW#Xj%wViBF7iA6Tpjx&N zRD23P2$w#>s`-h*BcH&s6L{0LMO}2rZZ$KTaO@z&W8}XX%SJJTBRXDT_hy{KlFR8b zY@n5DQ!)fHUd&qkC-L*UFzrHBK--{Ycl*4!=_e6m(!1cMPq35;x~zS9JM+x>=}P&t z$3jqorn;QF7K0^@z|PF`Jrl`47nKib$|%ET@1yoyh4{uJ%|tD?P+tsRz!Y0+ zUi_O`v9WuC!LAB)^B!EodP0bO z5K&Vp6p--!DCo8NAIL9Nz6^@=8YECF7mz4(th&0`8K8Ar-|$V-)-tJmin7g|LwMw{ z3?3nv>WX;Cb1z8!bOm8uiUIQBl2_!^L+$;A}w`B3tt`1 zIfh|A_8~rAMvZ-M4BKlDtL1z=g*X$!KbkMNL6vRT^Rse9)*p@ja@eLud5^vU*OFEp`1sem)=`>VyiJs2Fohb zwZM#v)rB7RS+~E3HNU4hjCKO7v+H45%M!?v-^Y=tr|E&Hmm)|2b&c3A`D3eCn#TQv zQL;OZtoJLzh^!IzN+APUWt73qj)cdIIdk923EqntgtWY<)9tSBM>U_1cr3{TWt)3x zVH*as6R#2Q)rpxV+j%rz&ilbMPgn7aX-}b}Sx|i=D|LV`pVASlDW2|YfRRyVVO{O% z?toABY!qg)vdyyr0oVt8d$(nVt!TkfPuR0rxn0Pi&1|TE{?_Qvnc(PW?VKoAk2GvD zw-cw~4GwuE&*~`#sfxm#n@?sbKhgVqmDb0RV0EO7b-?ua`!5zext?=iz}tGkC&@Gv2pZ)CZJfR6@Bj477~ zu;H|%^2f~UHId^~%zWlm&nxjZu^Y&1fzuvS@;mcHu5tL}qF7pI7)3-gy31@Kuj*nq zup-D0D8ofx6}o~VwU}4cUgYH3Ms!xnw`79Id*KlBCwgIgTDH;q1`!TsQsQoB0j9W; zKgs-M^QW4QizlfcyunAq>H6cBw>{nsPoK}JA`#h3Nn>r|Gp;whde=DlEVn=N(0rc*9A9MyfMrQv>iT2k$YA43o>N&)AUe5H%SF@{!IYiI%tfz4u(}C$~ zK9P%zp`gVkYV)39PqR~ge(z&vxmB59m)3;iTLOdc#^yIx-62RstR?Iml9S0Dx@qJN@sh=xLWi;d8uBtkCih8y7;uPa{+WQDh`Uy!kH!DDU2N5)O zawSIBqsKj9EH^@BU3#P*;J5DVo@$SfVBAj}#GD@c8CJD}PZ#|pQtbE?&|$=w_TFeO z%(nI-j9t#w8l(o<4YqQrm+civzwNA-K0kinO^Qr(9tJOfLh1G=q-f=q10zG~FxG=2 z&G0_>_-_qK35Zwb=JnA1I=T`_23=NczK0iCrcRi-=u*(p#e^c_=Iu?!Ra$=SsA?{s zKm25cr?mGHnGK6+Eux_KmQ(f>m*Yi=47^_F4Tp+_41?jWOApOi6?5udlvm;k2^kcA zG@tc@!Ds6lFCwx>aIV_n6D2&+NlfWzaAJA?D9Li@UDkfbkFa}aDD3Xe1@8+S zA})J@V!rs<`XkLc>>Y!vjB7rSYZSC;qRFdo99 z-4h?Es!YS1(mceTjW6K$j@{v{T;HC5k>!Mk!Q?3S&zPQ87&iktud{kh*bUipHU}{@ zRM269dIBm>pCF?v_y48P<1)<5%ogk1k&goJX5fd4Xl#G)v_WmW5jCJ3pg4z6SoP1Q z7ySS}Jba}}KF80qX=#ZLbq}?7;`$ZN%IjlN-oHC@b!48j3ZAmF%NED%?B6vB(-BP9 z9gWDs-V2rP#C@ysd+4(neQPrudQ`37D{){@P>lvHDFww`t|s#D4&iE6ru_VTYz&1P zILvi>*r4AE4l@?4PIpI4U+}p_bNFAmoVUJp`GQ1hj7zL<=|&G>fC!|GRQX>ZQIan; z_HSXPQ!Gd3m3lg>8EHQKR4$2t|3wgRHy?>nHQnlJjf#fGlrfR|Dg*6`(2Z(COhW(p zy{I!aXhLIZZ);d(Ms=MlCvW*E6BZSJpdfcSQveYYDqU8j&ibe|cEn_7`gc%4VIj(L zo@rsUX6-+F<9X6g|2iFz@1vp7Lauad>3&p>80@@IY9Qs}!buzn&Z9hne`ICOPeuRg zhSY1o9#EN|+U+(Oo1SlYrC1G}!Ssx+Sf~1;{b(p%6I7I#XhFflPoYmvA{YdV$mw@R zsY`#Ze8zdY@}H>Xgq+Hs9u6EIm+COU#{1yRtmVq9e_CB>p~)Q-3$RvWgj43~+?$+10K?Yzv-UoE`7Nt2OTBv+Lb z>QtEHOcNbRaR+h@> zt(-tUwF4N*H4z%)N3?!16Xk)x_%mHY__yCNLDGY$Xe`<9Sq|d&=$qvA;Z|azBF-qv z-%|$V))F$pTW%!XOgw8lrDmrXm|xTO`&G3?<$F+PGXaM%%QNE-wM$Qf@7GJSz9wpN zu9C}tM$R7ZJTE#NDS`aBUxz7_s>(-J$BhbVmYK8J?o-`GThg`&ER)v*fB6TmFBBZ~ zW(SYf*yv~?<3HnNQX4XTk3-%e>*sZ8vpIu%knG6osP!@c8uOdq_ZbCenV8`xWsm43 z3D)Wc18{(K%8hIk8GNg0G*xYNh593#y zUd>|&ICt4~{D=5U1~{*bd-+H> z3*CGO0JmvsE)&GHkiLq?l>B=AczN(_r0|ibJ>r)@egbAru+&%UL)yb+J@>gur#Hp( zGwuU=9{6A!6 zslCpFo+aGq32g?NI)E>tW7D_0*Ilia0}-L46h!t}QF}PkVPohuug_Iy5BrlM(-4TT z8+oIkC@g-6Z}>PysNdV1Zvfb7+Z&qlp6#-VJ^fFsYL51I4I#D@4fO77H;_7tx(#L zP!h@TUfT$w>Q~bXC|Zm6?WPy9Iv-wMUY44@5TV2|@zKkz$);~SfBTq>q7nsjB<2!- zQQB4RDaPrc;6Gf~m$;q%`Ew0jj>ex(yI)S)8S+fBMM!K~uF9x4^(nZkGyRZ(-PvWp znHRk5wu3rb4K?^PR>$*@{4YawM9eyMPkc7UPnU#QFL$IqM9 zmq$3vs@=1{2o_}w4}OhV*g@3Gd@1+IN=bR^@A~ugkv;$Y)&Ba74Q21;`9q)CipNeF zjLr#*WE?MTIYfAf$udXpAXG3G6Z(u zF`prKhc3vwX{gf_jp33zb(It=QA-hAFWh@<$(}k;y}~W-Lk+?dR=Kg zB}n+=b_{7rxYXb>!Y}s3M|*Ibhu2IB-i5%AM$GBSxA8XpLNwoZgg{LGp<{F!?zfOe z`Q>*WxbhCqt&r_{)`?Vb^g_KlikA-dgSCP6rP)3F=>6%hlE#aj{d44H$?-()xIy`*QIV&QF+ZeDiMn? z3eD6l)~5|?$AL(eJ`};CKwlh3J1Wz*pn?dVw{~Mf(m#L2%;G!3Z zDq#0A(LI+cEjmxB(WZ`Q{KV1LYXqkM)Shmp7yYJ$w`v?*o;d8zHDIJX5;LI)WDz`i zn`?;m9yIDXq(1QzN~qB28U{QW^BUv1FkEr}9F}9_icVXfd2r{vCB(TE{5Ia59tAD0 zJ3ynsHjuIkQk<)B5BN>tti|*D=0{w3b2Z82O#TdDvDv`W7rtzHfz;NQ>5|SnX0c#Z zCTxkFj^5NHJj7gK0eowU=xhO_DA_1vS}R_GP7uqAY23}@(vQ2NwZz|`aRZqp9KScF zNjl1<;ER+8GVW)k%GOuIB0Y<(>1W-{Il&1|*{?$N#|s&D_&hVavottMrNQ4y{IM%m zxrU~x=i|iJ!)BKqem3wp;r=zjHyJa8I)`McRVE-<6H-I@%p%W z#K$|X*3g}e+!fz;XQW-PthV2t@VW3k5Fx#TNWNe^N2m48s4`r;>39#y z5~cgT>Pol=1NlQZ1_+@g8cI2t@h#Hpere9JvdW66F0}hwrze9_dDKVhdJF^?U4gh( zHl3A-hK9!eRbQ>L^4B80GtFPQ+3&I+6*DA@@{+}z$R9(&+jD2|7kKT#VJVelog$os zmAukTR2&XMf?rl&zp-$AMr2HGl$TasVGqSOpHuuTXefR>F1vyv1sj1wW|QTduuk!f z#g4o0@4o*qdXARM)!df6hl9(hQ%tC4F z6aF6x$wHjhFnviEXOih3$#d>?+dY?$+eaEj^;20K5>2R}eKZ;1p?c~t0qv1$kp_TP z1|%_qklBh`rE;x})r=%ZnX8N(&FsOQK=g;h<2L>zm6s10$n`5tCMqDI4oDZ=+(I|n zeN{ViiT9=mTwt&eLthHV22Al<3EYzec<{ae*LrEG5qrjMV7#HBArL|zu8Pky+yE9# zC7(%4N=)Mu5IYfl6n+WPf8_{0*cC9@2sAK~O}Sn9S%i&fZn;%vEIUGPRFq6iDJ}y$ z&8yW?G9imStted{Iz8k1vExBZj{rZ7;m+ctMJS;{b53U9jKv38F}N$+F*^H-g7?2w zPd3X#ygb(;{J32|Tiji5Y;r@9^Ca$jS*_V>B7%-l!8}wGVNQ}73$L0ukiC|RWSMTd z^aa{M`O)e3D5vs>JE7q(gs>R-NaVHON0l5ye$WxoSqx)N?oGx-*zI3Mrpct?PHky^ zPGe`RzYC~A&eKquRcWB!-4Th62bOLUqV|avV@>JA#seQqUe%SwI#s?z9>#S;(~QM9 z);vvV4}2y=7=6hWGw2CbR{#-KM6W0>kJ1w-b{Q}+ih*_M*o%Ut`cbJ(no1d5B3M`-Ah?_L`d_ch{Rk>VdJ{Z|?xeNTeT_!*V0S6%P>9sjqYfQ{ToeFir0w za=o27!RnB2@rt5iSzQeX_xCT|UtcVjL9hhrV5-~7&)Yc+$#t7r4rDMlxqRDJ*b?xXdFc{t_GwRYF>cpG_lfEM@LoyVnOPiU6 zR9M035LwZ>w`u$!#uR>*xML_0vR?Y&D{duJ)%Wk8>OoO4>j_o2PGSoosOIt${x@mx zm&Ol`m$!Bws%*5iE%1$h$e)QNiMFv|-}pPZ!MyAA2m<-vh{>q?rs`iE6_B~^;w@y@ zmoO;Z#Tu=O!$V6IRp4^mrfm5k;|ctJ_XNP6M^u;05q&}`9fS4_(;Uk{1PxXut^aCj z4x2ZxkOc~$v6tqe(()t{`3hyprKaCXWYvWm7&Kb z7HWfxD0EB`Y(o4v-n52AqjobzXvg~X1_ooo?2tk;tS`Q)-2m<|a6(;YY~4Ryrl|du zDl#xGPJW|P2Vy8U_nS>4UfgI7nRboa|Ga7nA+dF-&~u+6;($vSj;kx<3mTki=;!V< z^jbCxl?jph`mUIvp`q(u3I-NqGU$4o9+n`ZW|QH>_I&!Cio%?$msS}U+F+Njlg8@$ zV%9mc&KUTT;HRgcsnkRZI2l$efuG(voiT37frWGA>H4=HLFZ`$I~?XWB%Pvq>{3PXny~|x)yM6Mp38jz_D0kSbNiE8Q)1wHSA3!a( z(S``#2d+x`-dUz`vIl&80cubbOyJ*T7FN*AakpSY{4iUhclRbRONdk7j(pmR&;dXf zR2V>K^`-5PB@9?j4QY7!tz&$BHT*DWWh*qRe-Dy`!25oYu9J1x8og@t@Ia)dzlA&r z2gA2LD(JEqW({-$sWPR>aN@|+l}Vz3#{x* zqZYq&cbDV8Bu&sKK2$0*98eVUc=^VMm8#5*5KwTcBYtC2fkdXtXqpH>={EnP{j%3P;zY^{C=ifMIhYc=o)F0Um5I)1I$_WC>yEe(> zBy+1;QmKEZ>7nGOdT6w$#Tw%w;W3>aQ4p962J>^J{!bc*qe=)%lid{eO{<3462*LB zAwkN_3XST%I`3VK{22{OI>h0w_t$j7BP=&YYUL%LvHisD^em zrt@SwP0t}AA9+}kK1061S6tpKoDIl$-lh@r@RgNnQ7X?2EDVb&{%Zd+H82r#WVNwF zVB^Av)ZJ|@k^Bd+n=_uqfht*rpMk#5r@q&9H zgh62P#6QDBKZLUirUc|i65&)yb19c2lOzHo05Zq=AAc%Ay=VJIj71SW()Wy%W zW!L^=EH5vWY%^e`hWpPnKCkHee}96KV#EkJ?}Fx>m!Z-yiZabxu% z`MbN8T>rM${sd#SkL&xtCNX?CQmWpqvre;K4>X;+FrB;rPrKr`t;?C2!4CA3iXr~| z=PCzShfx1ze%SM0dNRkf1?zoJwBqstu$O1}wX=q=1IRCxv#v?BkHbSSah`sDKsF+d}B&8nRdfCht<^s*ni(Z zM#4aaTQKD=e-qmz5ZJs3O7Lax#(ck z95(tbq1kJ4I!|3B4=!9vG#R-W?>oUZ0 zc<>40-EYa^x#79%D0shj`Mp-Jo`)KZ@9GOK!AtlPE(J`zp|&i~s>{^&T9@T%y5sqOfvLi` z*HHx46P}n5UuzHS2V>eCrYy2!k+g?FV;zIdJ_?43-5v_a$GsR7RvO+{#3lKwdlqHS z-Ku0A-*pXwmO8R+6x-?#UW0bYlTWc{5KY%d!DdH}0#}neE#u!J_vJ;=N7B?-Xk>I#vZrWBgg_ZjuD$ zx&5F6mg!pev_T<`iD~<%QI*y&FSiVyh}!64BN^^9d}uQmye{hquuyJo_;t&fDOn|_ zU$OL-qA=InlDYr3W+!Q6mcF$s5K3hNmN}iBoosvvM527eX_1`YW8`6S%%F1~Gu{1V z-Nw}FZx(CC&gxky0`AswiF32|i;L}cM*j(TjIf!lP^Gx53|Z=^49nFFpb2}$7u zr;IMwPH`A-$QqN9Rf_@2G?v)n*^klR-;a#O67U}FpDF)Pv_F+QzT98`d-5^OSJ0d0`+cXFjRKtY)%iNo5aaZO#t|=_C@-aTdBQe2 zexzmEe6?Gt*$*M{PlF6X}= z_`i_P4Svb@pQ5j~JqUwP2+T`+I(FJD{?%Uj~*!JjN1cP8`6HEO&xhd=U~2nnAKU-z(8V*(F7bp;kXmdCR@ z%3ioSrDP#8dqmX*YdDc~1%Ud=Fx#R|AJAD*tySUaOaUNVOx@*3fK`-IlP7)(>l0dS zv_0PF;K|~4rDw|3(A10=_%pQ}d4J67f4{I8&g0WOe?JQ5Qu#;(UutjZE~YTTnek)R z4E5di9YvnuIic^BV)`%S%5sh;sLUnrGDm2-_mDHoNNk93U^*bSkNkSPgd7@IX}QUW z-C5rw*$s={MCI1nV{gNCjs4Iw8ObAKX8H2=1&h7X&y~3&NIGKM3I}hcCa(XlJIiTJ z?4v2+;UdyOjly;oltO&7(7nma{ytZ2Mwz3$GR*pvUnq^Bd&J z@Cwh+Yp;tHb5G^fh`yEbY}=UH2O?^v-BwhYpP3w+J8}xU5OiHYP3}F;F+Xb+$+Ttp z$xZ|W&YUH0l$bd^XW~1HS_?a2f!)$aYZu^QC$D#>F#HjPn@?w7^L#*cbyD<|OH|AQd}QhrM9we)Rd@nusI; zG63-tE}B7Dl)JAy*^`@eJNft=S1S7YUn+cZ))6JHCUcX^-xUrwm5(_;_CzDa`@*86 zwME5lOTIL}$r{CJ;VjSw45P5LxUbued!CSe(O696J5wbGeR<%dW39d)xN9pw;}>;S z^x)Md_nCTb#(TaSM$E(s3b&X`ZuDHh9CTjZ{y}gdJI5z@!w32@8Z?n}y$R6+D zOp{sn!ulIr=o?{IB6ul>?H*(F7l2!BEf|Q*a*5)|zTWpm+C#wPEXj#mqdiMXkY_t-&L<{YLn zDwY1;vU~~a9NOU$6w68j)Fx^aL+|Yfd7{D zB#J>f7S~ag zR8{}gCxP#lqSo}jJ+?JB?|o_n%vEoPFLw5~;>G*w+wRb&nh94uG)f3^5+I(_!W>E4 z!o3KSucK*pzCtC?YfXOqvhCA+L%UwI)(r!}WdjNt-=j6hsU?Z8AnY30v3GMgQh|kj zG#nC=SHJnmm4L!>d61!vS>015FeQH?YbhByz{FuGL5V|ZRua&1lvFPh`{Ic?NpHTh zKXxndmob|a4n3WF?f(LcA^-nkF)Fr)Q1MsKqllStpEnr0wv&*xkPkgN=qetlL=GLF^Shrjpw^#k=?-NSKHxa_8 z9{+7cDPSwoMg6k5vfT>GgLax}W@06LC%VOiMze0sTnuF$u;7%2(#N-!V*g70NuRGL znyeUy_g;~pnG(-=$16MQI(}77H34LI2n{>DG2qUVaO|&{=mfKfp8pAo+bUw&iM#bn zeQRQq8KT=*J=DN_fEm96XPSJE1#3VNx4_n8<9>3J+N}TSqEF+Qady@tQBI8h@LC&h zrpz?5@Lh>ss#yg&yCb8nkv~P@lLGyxvT^|?wBJyKCXVBz2~(s-b^~Q%z4!vakKt@0J|q%U0yKCnGNKXEsg6 z>cJRWqv^JFBeu|aKxDfw6Q?Hl;EX!f{Xhkl+{7Ad{<%YfgIV(fCSQXR(Iv5l(aF(q zcN)p5Y%IqqJ~T!25E25JPP$079C9lx*A!M8sx*$wLm&{hAkZlhFVMSX&DBtFWwob5 z(ua2^%H(}s5gv0vk29ZzO6BCK z-#`Y58j)|IHd}6R-IV(QJDt&Blr+>odvFVdE(>NT@{_*+iI&$_uJp8O`U%5Vb)V*1 zM3UAJBS`__uhSnhvwoXT8Omow_;|>Ar>_zmhU$~wK5J(j@mVW$()QM}AkP=k{9eJL z)xAOFf5nZ@-pUJa{R zH2!Q}bKtqt^f0eyc=KZ--r5ry4gYHQ$X{bmV=MbW^lrz5q`3n^FMXv@+=~NYl$-m7~8^|C~$)Cjwybgr94wL*H>iQ;OMahG#N*K(FKG zLOpp$DmQ9WEwjxQQ8}LvssH%b8_sN^&A@YI$<$}1owGFQynJb!SxBWfVEh&@s>*zY z$Oqt#2lV%DvCH*rvb{ENVV1nQY8KS+F^v))BTw7Kwkm$rq@!$0bnd>d@gx%Ak&&h2@t+i_*zI-XL7%<%*Y&#|c(j^q zB?JY(MH&ez{xY(+w6ruSD4wZtUZloZ4fqjMYSNWdK^;W2foD=8OKPzHdUDHDN_W`8 zYBN&RPBu+{(Ic7?35)UBj3yKaL)+{Wmm@35=`SMFwP*NBjz5UQ?z*aWZBlRv{5{!~cE;2#zzKmWZw$E(N0H8I5?QVWW9pH}7cO)G(^x%8{hGyl z)T0%j?9Tvtq!=;D+o8pBm>SAhs<(tH!{Q(QX?7!9UZVeePZ(ZRMHq(kCM_;5-Z@lT z%gpJ_4WT<{xlk&L7&8t2)f7}wwwv$0D51z!Fjie6>ADXTdEW(Pk$TF|F}lG!7v9wM zQ^BB18gzv_*6znRtJ`K}(3)*F+!kP81sO>`FMNtqr{&c?6$tMZSsBC2HMI|ncq3}h zF!`skCOcYcp();x|C#EM+|N=x?aHV<4h;*7LO>w7J6*)a*RLfDfCb9(N>iG@gMhT~ zd!y0u=`x>NwsaUReQiX&gnm1M68NZ!0*IUXplc>GtXFJd~`H*4M1 zd`2E;n!I@b2L2EgQKMmf&nK|g*H+!*t+Lk71;om_N_9d5#$nq}?+J+sk*3G$Y~1LI zJb(z3jV!*7utW49r^`^D!PAdBKaNlc3z67mjpUIHe*Y@_y#CnHku65;qas1Vz!u-0 z@FaNQudzzbq_gExg1#735)&A zYFdQ`@Bx4+Raudjq{hSA^L>ueCs}QRILIniczLlhq1=ymeZbp%Nt#3vAtApzA4fZM{cJ`FjN5fyompNP*CmaLO6r&mMsLR*QR>+mxA2=ftgz*qkHXW-XE$Ee*Ri zpp`9`KLPd@pdVCifWvV2yCD*qdL=xsOC0(1v8S3GQ`r$>;EeX_wrT?+S&G8&5+z$F z1Ch?BrNbY&Ft~v_r^tz&DuYztpBpwSr)wbHA&_U2YjBeYg*F>otSW(<@$`$4KkqQj z5Yb5_Be_ei8Z?G#SWtm)*PQnw_IxnsS!qx^bwaz81-^p9bk9)Eur33{-yi#glLzDAJc_uLVX)`dopIw3N2j=bO zQqL{`nk?Qg)MjR8sL03) z+Y~kpCnBf`i6iX7lkEenHgla^MI`>tPmA$g?oAhj?k9R$R zGwMmFr+-wb8rnBQdGmeO{ne@I0aL zOfBcW?uvE#w}J+Qc5E)+cLb5jQAP546Au(D!b0D1lEArNu7|e6R2l6kt)_~WAaT9W z6`*7MjpeIlT{omRoipu~r0g~n7g#f5SSpDq;d2wS6M9-F!kRsMP#U$RS6W?SiS@IE z=PqnL?F?8h@Rnn7aThxRh&eOrIbC4*C~(&qkVS?%OSp5nr*%2Ppb%k17O~ad>VN32 z`WI{FBBgBdHxz|2octI`B%f(^G+t@2mH^VMG+s+3V27059nUc^JZ}3rcTu7U&)bP* z9rgm-k8r}j_PJAoW@)*l*;MRPb1wcw5H1VJb7Xq}@z2Xm`dG{-hTkeOC8m@gGB~}W z7opL|%E%|3|I>SJ6w9PVMqx1=0Obnvo4t{G%elc_ikY{iSf|}@J9ReDm8%jtU$PXP zc&=BRoixB(q@k}h1Z3OT>~I$LRox(gMbCPBKAt3Z%UBNv<76$=rw6TT$K9+H ziMnMf_W=DTe)t~l8o5JNxW*(Ko_T0cwA7AmNKAH~#3Licnm)}i9X!Hki~cOm=CH-( z+y(`nDrn>}(MB#TB#~C83r%59dzUV6+=qfNFMYk5F7kEl>zBGUS@bj?zFr-m>Efh% zL~^ial8>bJkzu(S1;~G@+NI9P8!BH}x*IbzvzOcv#C(K>WAbspH4}yN7+8x>ujC0T zC1-i~{9FyLdexcr{q~@H+HL1tY0_wL!v0hBl)c7#O0T!C@A#nVchW4CR`@8;VL55L zJ6L0JZFG^%_yZWw>k~(FU;VkoglXPyBmEP_WZAJX>0t}yWJg^#ar8-+`pleQUR!q8 zWr2{1blf6{HT)>MqQpCUO3`d#rdsUZA&U%?bevUTK9y}^YI@xbg>?0>YM+>vrg_5t z%%Pu)*p=Ep>;`T3m;sC5w%1kib|??~enZxU#~Zo;%a!xG<0y#YGWp_~Kv*FtN;(x| zBMkLz8}#V29PsD*a0&eqfl_N6e#v>M^&b1Pd$F^Ys~IYJHfLWVVb)#%)U>MGYjsM- zVx}AH4my;0SPW?*O4MOjP}9Tw^&&-QxWhYZD-Af1~?n*;FqCVP$kyv7V)W4VZ4Q z=)S%_&35yYDq)Dab5j10MASka9-K&gcM87)@`_4R>Gq%X3)B*9$o@+o_^@!>LJoRj zti7;Z_5NMFZ=Eccu+#M40!Y&SkX`so-BA{a#u?ol^(vqERPW3Qk8S8)lW~VqBT}ld zaRDVYVf12|7%drcG&=3Ze{BUXSA9r89b#%cizlT>HUqOQX4eAGTzpe<>9aHAQ%+8z zqJSehW=CwN$rnv5m)&3b?2RFpb6W}0e1t!(_RC}~ODJ`GEYY|dKN)!_5a$$7)a=>g zzS7t3`Gf6dVspsZh&*2jb=v50A^S8Q6tq_e1^TN8iY29_$k`iU&SN6l>#1-V9Y(I~ zXpgW0x+)VYacUGEY&hB$Mla5<`&S?kL|K`Q`oCY!bS!&kiCcvR-PMy8(Q)>6&Z{&Q zAG?f6hqF5O?dkE(%?9-SHddLGkZ#kR>jT_CDK%6pijwcRZ9@FBs3O`iGoT)w-(T0$ z&?_B`PWeMCq|A4VNKw6l(KP#V!T?drZyJlzbxn4pvyC<+{45kEkq;WLV`gtlV2TeM zu>@ik;*dO(WWP%{kTEe_W0q|WbevFQgm3gIpPw)YW-(|I#K3oMPMYF$-ovm_VNyba;! z+mC`C3k>Hxz-`N>E9REefcTCh`|#$UZ_q~J_o|osI0%CbO%hX(x@eS^4L$?&ws2B?r#S>0XaZ0rEFSYB>3T+1n7kV z$St#z$y4i*RTb|S=bS@}47=d+r>xxXhcIs2nc1@?XHk42yaBIxAOZC)SqAzRi(>)k~w=H&h&-cVZAlN`O?hR1j*4$dlapbKh!!KhB zU{Yt#Pa%scv_^fDU|`-z@qcL%xS#z?cX~Rky%{zJW-AKO{?pLY1u@Z{Yb7%0f=5|m z9*dfgHS(BYzZWF`9>zA5j3onoG}G`I%iSWzcPK8^=hY!M*AlQlD)CXQSgpRF$9!7@ z!|Ar(Q##=TZ|bW%vVgyTU|>+0XRvA+a~(D*xEnmeRGQPyr2U7z45&E4gpl<^E%0m_ zS+2l9S2M5#VM08yywNVf!{AWF5sdU=lzlcO@)GXr?l(lbzHqNnvuKA&;?SN^O@H^~ zY7KuSsG2Q%PmSuHyIC%Vy&{YoC=r{mdSrduHYOZ(uOBIn>fhR^LxyT&qjoJ zgNIdjpqrD*gA$$?I2&FlDO8Y0&vG^|pLE)|=;;k^glIiUL*YkaDYIwx)?I!(y+Gwla8ewhJTCh?)XO&`brPL>5Kq! zoyE<3U|#_3Ss$_X7ZFcMeWg9JoT>h>T4^*fw~DUMy!PsaBrl({%i#%#kG7cLvEx$0 z%9xS(`Mm`Pvl6kEYbLq-5imL^Bwcj1)+PbVr)}i=+7E+EJRwPg@5EZ6hLkO-LPICO z*(Iejq!z%f>dZMenBL+ za03V^;*LcH$nT%13d|>;UYS@%3KrA2SZ@9J2`q}TxSTtknVmPDd?uUngN#v7j^&`-+`thYATSW?!aDA>+>l$gQWAF7(9cJNQAE7(} zxC^(QJpa#k=JtAP`KIp0b(lwusu5X=4SC_=cPdpBRw$nep}-G}j-yZWe^uO{>%#AH zv9G7EdvQK?u;zVwOuq2;EJ4m{&UEB05*vs|qi z0hzN;EHwr4r}N4|MraYz-@}i-Ddva~6aO|3dh!tyC7m~$%AR`}(9xe1>&>||Sj~BG z_NJoOn=6f!fh75v*xT&L_I^4HJkY{LYgi6gT@Y$uTjU0ZpEM_EDDHtqA+zr28A68! z1tmhIR0SO+Ldng}SLOc4aCh~sAAPBsO_^;&9s}~3JdClwSq6Otr-)FGfgB$H!T~0f zdxkSftHa!Uk0|X2BtDQ%PIgx@-E?2r9>=@S)#J=T4i8V05$OyF1|@!4sf5zdw7-OD z;!yVN%pB!7U5n84+mYbp20A$~h*kO{Co+VI#M&Ra7~Pouhl?6c9t3nkPapi8x4m({ zstg91JEZ@IueS_~@{1ODQ3U=-2}npwcStu%NF&nS-5?z!-7VeSAPn8zFw)&Il0$dg z7tcBOxu5R0nP=YFx%S#?uiskl#zKmtw#LMaJ#MVGzGIy}AS1_8DU{71xqzY${QR7g zAPM_Xo7G_Bi|aWNz;xvNp4P>sy-%c`>;9K&`o}7=B%|Pw=C-OT&54e%3E$9#u@6OF zGa-U0zYD;nVnDIq>|e>IvwoaD_(+b0QxBWRoQ5i?T+i;}MHg21UXZ83tT zm{@b}H$^eZF9Am3POi${`hcjchXL2CD_8LRdA)+WG9N5joEa2~A$*P6pzXs6M|wOj zL}rj%3P=~_xA*j6A!7e|$Kr-+KbA;Ochx_ZXtJT^YkH$#w=qpdrIL^K#xcVVtQ>q? z`f7BA706076~)B(@_-t}tmS+|#28el!sfpMQXPb2?6hs~UUop-nC9PuE71@SzCpQQ z9H02Ih9@TGr;r1zl8}pV^ld~{vhjpswi;pJ{+29?nU$R*;FcXjs2^wexk#O0*}w9! zHga;sb@n7ybz9QD4{+GF7%)mn6wgVCiHYS4%C%yxOux1P5vwq8ZFKKv(@%gL6L$|R z!)S>X-n?n2XPboN01N2q9Z*P`QrUAqEK>kI&#CD&sG2g+BLOI4PT9l+7^Zf`aPW;% zUGC#;DbAyrHy0~EDz10f+qhT14To{45tD_&frgjGD+q^!89D~K#ltlk|5^z+H&$Pc zIeWVO1q0vB*<1x{lY)G8%Tk#h4zV+L)=oz%rfZug#)jrPwlo^Fo`O}(DtvuhFag>5 znJVZhf9_ia)62d^ukULQ3!jTgN(8h}j4j9IZ|1yWvXt&vIU=66Ncf@#gw`?MKfask z;&VtpZpq29eE5)Y(rAS}X78QoAi_YGQSJf5`?cR(9@Cm53xUUxQK z+Eot-tNci+w(awQGlaCHo=?p{7|F5F-iOR*^%r~E^oYgQM;$H_@2kWx19G49o2+i- z64CS=5{N*DN@#&7Ao(k54=gE0>Be`RoPSTnmYMf9xnQpjL`HG#$N4Qg2JyzeK znU1Zp=<=QQ1wKa9xFGqBVSeEO8tCr3r7i~Wu-fUErw_z7=;U^6T$d+FO(O7)!Z2 zI^*I+zNACjXNq{Ch^Tl`sqyI+5foHRDeC(?OgoN(qxI-T>+l}B!f}&UXmox4xt*fT{V~B!jkjQj zI<&-sl9#D8+Ge*e>p5L5+F6iaD`_9&Y#X#T&{KBxeOI2GsX7#VzqU1T@6#<)Am^=D z`LgCpF(}gma{DyIUPC%GtACRv7$8^>@o0~AZG9D0O;L9)WTb>xsok{$s*;E}ILwr@ zs7z2es`XU0|AW2D&Uv}8Q=Ds-h78jOZJ#B^$ycQ##V+u@Y^O39r<3s*r$u@Xzt#kA zq$J?eSBLA_ZCSBW+@NZWAAvkL5OnGJQq83~BccP!z&ILh(Sgp^)3|Ab05@%?-M=f1 zLLj4YSqSy#JJ>{skPG;wv9^-}eHy3eaF5Y@-o0N=NBP#>3_o*mWF3x+L-;i06#TQi z?Dljk`Yd|jx!cv0>StZFni>)Djgw?pNQhX7xp2%mLa2+aL(~=9TO>>0`i9n8#!odm zV+Mvp8%}UMmTyH{O}lcO7=Wi0296-dn!}cGhLQ~F1AZua+n_n??X2e;Bu-Bz+SWuu znwc7S+N!dPfUsls_riCehpRe4Yx1Ems$T!WiFDg1tI(y1!OROIMHt+Wf1%;ud z&wIs4{A3@wsZwCHa<*F70COl#8(7r=@+L;3CuuhDPO&>$Gy7HqLW1d?;#)8`oZfz+d3Sp(kFrnUGrjdAF?{(5Sja~cu?rL zB>M1BC&f01KtV9wK+^>wi=DlTF6;ch#n4kg)v4N&oncd z8fRy;C0*}uSCrLVj`d_W!6bBt4WUcKj)xU`=@7HcZvMvHLBjzhkkM@kvu^c9FMFK~ zwzC}ZKvdygo6wE`uC}I#*SR(;;%Sf5UUuboK%a_11Hc{T1QdaxShQbVj{4b*zZI*A znqyPD^e8HYq`1-kDSJaJc_`1}jT;&gAWd@wabEq#7SyZmKfgh0G$9GIDLGdcpdePW z&gE7v&#S479nK?lU-Uz%+P*qq**cRkjUk=$sE#a3Ks#63ni@=DGO!vU+4H<8d*rxPb>+)T3!ri+N4bWNp7 zQq+nWG0#!6`AQymLC=RHNDRKr_>F+ViMo#X;wa(G^h(y|lq)E`52bQ9$X)bhM-36H zwl{Y;jsm8ws?kl(DVeG(DJgO0p{jOMHrUtD+VVc0oC>YX(se~dW@s4IJ^P;#;44p$ zQxRloxeUkFJAl7Fx;q)I*Mp=$Ot}+Bh@S-)#J@^dIisinBXb&+jHBCG_U$;CsVb)w zE(!8~Vj4QeW_(-`p11k3LHyj+Q1uj|2ihxYZP}}OaG803+~M_Z9DSC`_J(u$lPNN2 zajSx4^cFvy#?#aNzhXA8!{^fzFw% zq)JjyFuvR;a1p+s!WAZoRypX%Mf?D^g*G3;&WDHK1)O1K?!!3#c_oJRcP6_ejuk}2#9gm+n{fbH`;)mM8&{PhFuiECyDy?p9WGVR;5q9 zRGEe!%OOXkgRb>pkUZ$M*XbA2g#PHog1#}&E*+(09CRi$5%Ag;w zeE_-}P1b`TSLfUq$uk)oWw6^TtNk;U#}^{tCY;s&gK^wsW1WC&VEQzTpzM zQkz^kU%6ZSi;AHcxk-c=;ulxo=&#h>^noT=SDrt6NP<3RzrSJVzI;x?~2{ zIx{53L{3i5Rg_45k21g(mdL8u9juv+q-&>{eqYLxqu=-@bc32m7_f)B1HXs^woIty z6I17e%byZ|n|lUk-8{>_SFGPuLVe$j8@!k-!QwB6qBlV=&mwER6+48C8|9aZA>);* z9=7N!QzfdV@BKz-rg(~P3~)-uw>^B&pd`l{=SwdJhDwa`yZC-DgLeV4*5S+YDU;^k z)77KVMMi9qZ=F<2{S6qd9tf<;*4u*zp!Hx7W8o+wHZ?a1D0qOxCw7H1WAqbou8H%x ztWCYa+*0l7jiOmZE6X=hHPu3i}&{6Q3jFAUZ^mHdGFo(g$#D0=oioTrc_v|x7?$maSe(QM3rwZ z%*{?&;Hq{62R}W^3q1xOO<%Zbc<=5`hmqRfXRJZ%ux%IZdMX<%dSY<|9?$sXIS_6A zTSgkr&dwR;6*rFcz3(Y5U`eUob|+PHT#lxl19f)Io>`nE?wM64iIk ztz5s&uI0SL{GgvB5MxD1NiTbtj9z~P8?0Q((M4FYB&1xd_{2s~3|P>Ve03N&6>nE> zpN<$??;(f9R?k11budnc#Ix3e55^7r%k9^Bus)6rhxR>Cg zR(K{#!(}9+gf_Kk@J?(R0emB!*5lXX=Z-lZ<9KNq;0&awk}F1DC(?jBT-rPSQlD6^ z-2KC-q{+VDd5HJ#WD`%}zJMWQAMV*|*qGsPJo9?9)R35R#QS(it|w?XH>NV+^Wp{M z6ukFQCsg;pm)a^1Wo~vM%%{5F-E+mbGk&f-`LRi)x`~r#P+KF9_cCBLU3h;MGuC(h z^JE?KY0uJ>GTrFttWEiTO&J``J*yhacQ4&f<)_k?um-xcwN@`6nm%5&B0 zs4}JbJkjC$JUO7>*p@AH!@Dx>mdVJwZ{dX3G_(&~HauX!RPHkESwN3>I*i&tjSW7& zuqPAF0q(C%SjxCtki7Ib~T z{QIx4`wj&R9+x4*WGs&IBO{9_~sXq+#}Z+cBuoXQHiDXJL--PhRUqeAREa z2}9h~3yb!%@T3LZ9oM)oWtkKVq`NIy9r1zTxZuB2Yg-KrQQzi(;7vYuAn{=H~JZ51bxOWLA$Hr;2X6tAw+=Uzb^;L@z&+E_(yl&@9;k7Yezb=y};U zpX+V~c|UIp!Qd?DDrmS!zy{I?OzE6m*NE z`eyNNhSXqJjL%zoJHAu}8I>|~u*-2h*Kl7DB(-RDy)0a)E1LU0Lkw&{{Ok=iggmBY zl@;A5gh;x5SJ~|RhEn?|?o^k%Qi@d|SSJFUjI+@By(70zwOtL~TCM7hk2}Su#2%JN zm9K)+ouM_24@P+*NFk)d;tils_YW4m(eKl1qkQ~XT?bUFW1%Y`8kB%k z2yBLJ1Gi%^AF<`%dgr%n4i$JR4S;=oUnHO>?9bof!EF>@IuG90$ozX)a^Q0MS0T#~ zn%{B*V~M7z+dv&443qrSS<2tFJN8wwWpBjG;rm;;BG;OS60@5%So#i9$DLKZJlp@p z0thI@FR_gCx*;}rIbfCSopO+9jckG3Qjtj0I`uj@GADow6q;P%wMJ|UXa|r@sam)* zC{3qz-uF5`^QB4a?SR^!6{6%?Gg&~cpFUg$yFUlgEG!Jkus3^DweW*hm=K=?mo|_U zGq7*2Nqth0PerWxM1fZsR*7||m15+EgKi4glFYH>X2PCcSpvIKJMLe5jWzRp7z#N# zd{Ml>N8jo>?a}OpRsErQC)unFKLZu8(E?&=ur_2yygIXm7t90uvKIVk{#K|d5l47o z_-TKMP8xPp%3*&}2VF>YWO}~tv%)7vi6HEMUaC&?RP*lq%Do#4y;zweGdT=Ih1$J` zRc(}(zZpMX9<}HRZL$;mx?jY;N^7!mtQn-s8!JmQ4bPgqcW%Z`G4u0W!qECDCaYpq z{x;IR_Q`T~FlR2yRFM64_4?SrrF3F<);4h`>57M)hK;=_wt$o<$99*8Xn?DxWgOx7 z$XaNj_r@TSNL%YQg-~Dewy!xYX%|{nqi?tp+PW8YVb&%)Mr(IXkD9$}*9TRhOQBiu zwJkz!1*)N+p*_!${(Wn^M=HTho}=c5kBQ1{=i-U!gPTEFK9T$qp05Y!nu;`aUWeSaZ$;h0B zPX>+1Z}tcCjE$p!AYlr@z!_$WSR#$>K< z7k$lu8QVz^0?%8=gOmt3P0*(|iQ0D=n=?6CT8Z{&-eJa)?bS-s)t|hr{BTA8tX&fe z2JglzHl?Tumz!Y>S&@>gixo(D<)%@G6~jgjdsNZBx@7sXSDi&J z>DqW}?SEC~nxKEMH#gvB^jyF9sj}^u0C$v;tR$Yd zUuQunCFLALcfrFis7#{1X(qScmMXW4I|ecnh@PEUr`MjYy{&+(TyVXr8vGPi z@w?w>M9fI)rbrF$a|HuR6F=(8)q`|6B5UVnPrFVTB()FX8$XI3k((AMZ?~_15?23Z$AWX&! zL(Xh*fO_k0$8k1EXK)^aTPf3%Z3>A$C#PjjX8~b`K#Hqbv2dHoE-brC-M>mO_flrw|9axg?mvGf<1JooaIYi`e7vx#;1A z7De4PNqT~I8XgGanD6JYM0L4zi>~*@!0u~cbJ=e0?YAtW%!YmChXX}x&Tprnf z$CmRiuYB#a>uP2s1C1I+T(y_CgS))y@PZswmh|+Fog&8KrNJrYnr+sJZ7*`rjtuOg4N0q+QPy8#`_G z6ig~G%3#G+Z87DcTDjc27d67zf-9WP0L@prTSPe=%7h^Jr}yHHZguw(KUm$;y=Bgl zlMhZYT(X(Ja{L<2I}&x7Hs5MO0c$<+JicF1H8frAA2>7WOc^n07^mFp%=3CygMb|$ zak*^VvImjDQ}Dp3d$xxolUugVWHz&nz5R3k-)Ptr;F&wH>a2 zBQY9?ixMe6VSC$wJ?e$7-?MapGcnfmhDkwZtSy@?>xsPn4)yL8k#vEm3bw}QV4$LN zlB?r2NS9JYnSNxi17ow{J1T`o-=b(!ry*@S6~l%q_MluVTa)H$U%lmLBwaTJH!zV1+8MVSrb3cqGx(JQXOztnC;XUMsd3|=y5up4B0uJ6JMWB zR*#!);v&KF}<@N#u{1=ec^=A|=M1>rLiCm#pw z9_p2z$1ID@hUYs%jPl<<@xMC_u$HlYKw2lL`3VzV-;DjLyB(@mo{b(tD&TwYRj*5& zm$))~_7!5kf?ZNrOk(u3} zpYgR5bB=52CEM2?77h`OcaA}=PmG~zqm)a?JSdGnY;mhvQ^&fS7BW!9?rr96)9wUW zsjXg5y_I%9a1}NUMW948S#;Lh@pK)h8hN!&=5(xf({xJ-^4X{Ixz$C(WiyUwPOs8& zK}N6{nKe9Xy1f^s+^_>~m|FvlGhF^;4?R?bveVajzqOo6H@;qa)?dg|Nfxo5#jkwW z>~L_7!j|{M)947s12qIFMaqAYfI!2An}fqY5fQh}65bv*z_PD$l5RWh_1<)bC{Tbb zxlYG4bQs0wmV0lKo=3-X(;7J-+^Z`c^3Zjen{j`663^`qnRk8kmT(jw!*kCEVi#Ok zo87BiZ=09iu6uI1+{k%(pBngFZj#<+&3!C6dE3rwhAY~&re{%K^NfdnElzCmVY+oSKyK39C!xcp$n9Ekfb|iXbcKuD!fLu|~ zK&CMuY~!lsIHN%g!MI6_%X@J7HVMIa0jphFTAG%g{_Uk@h+KsawBnc^N8Ea_6uSM? zqpUbK4h%wAFMsu&ti0F*H>S5r|XbW+LE7Z)?s`h|2;8q&Q(CIJ9w4tBYvcwne^9aS7>jzdRTpiMVmA{ET zkkF8eOkiYzaZmz^MaFn6QB_tkwEySqAdh_cg>tjxF8lhmO2Yhy$XLne%leldkypH6 zvwTN+x&87wz(ka6VZ0hZ_fG8&S~-^eBbvo>5TilW733;$E` z%B7`4J<gekxLT^IH1Lq}SgC@s2ocQ_>goM$#An$=c!z%%wa zFVE!4QzDQ9!WHVZ2%(5C#W`Y0Uc;-+3YX*o=sz$zLF8>=ALIPiBn#Nywmuz00U6;3 zDDBsLP-eKKvC_Y1sFnN3ux=3@h1CF80f4MM=w#o=N@o8n{yUF~hWLT+R~}$mKnRw? zYIV7ipGu}?g-OmkxOg*SWOwr4|}FhdbvhE~j4LMxDkT4&@Bqe@To8L4kf0i1=oJqc|1kXlJ_5SRCI@gv$>bwn z`PeqBIgyih75MIKXFGYs+`D@-{BR zLIT)dL=bECwN6F8G|&AMzPOMI6=G&74%M`mfng(J=p7?gta<*+2y{o4CWv**=%Lrw zWg#U2PrUcgOqh4+#>K>}M*3F@*B6zF{C)VBQqWbXf}(&$&lIPb-P1;2&Hk^PDT88l zmtEAlx|!+OX+%%&d_rb5R1FP(Nhz75nJvq*G7D?V?CKmg5i9D)4SOC*S!rr!p?0PmWznzEB{2B`H9PRo6N+_&yLb>ml|vfb6eAEFD{s~ z@+#|bgEx%7$)hJ)Oius#^FV}KNb`yfRRCh{3u~%SeU8^*WK2z4DK@?zFrIrpY+s0sDJX!jh@=eHSeWGKU`U{DRw*7rgC>j zNG@DzVMNk5{8F|)^agc=#qCo>;Ql6lR)`*)ck8%xl$Dw);qC1mo!PVJI59o{U%LrDda4oT zlqI?>BMhY3-@3-aMqh`rA%{(bsIQ-5D&tOw4ykXDh17F1VQpeNw4^nAqeoiVBN)l% zsWhrkmHt!2S5q#+*UuDw^T4iD(2!fv*Tnx%Iw$VZ!&c$V^qg}+F(zDUYqhg0N0Uua z-D1y616S1w>A95Z0DH!L8vtzB_YB#3jSA-$gd>%ffRc4gZRW;F1_gTwM%rp zn{5lFs~yF5D<%&Y`d9zk1i41Q@R{@k)Ggn9y|4;{v_fDmy&}^eK!7Lcm1`gTKKFPo z;Ca<$#B|n_tJ?g!V)3ad=D)y&RF<2qX3TxVUz+evy)nOZYIQjiux)W5lJfOYwDAjy zG7R2TIjO?xBjmdx8@$Az)?%7?4R7~n+tU^WwMT2uG_WUmQTbrG#Qkq-&&IA3F#-On z)2Xv6!t$Pyxwb#Ue?|mop`jh)iZ%WhjdU)Zv2Th1BoDz96j zS^geLITxF`GhsWc-;B?hyDL1-I!5s*9Bwy_IbEL+=-rpL+ms$db(>{ zlUlbX&%Y^d5eWE_PDvI5Op%Lt5JAuG+6mb0Z>p!7uz*dF+z{hPRJ`MDuS-JM>QX8Q zoegY_a}CH_UvmH@WpWUKbh@Mtr`kOH)ikr^k7uUi|A&{MU2k z>G@n2rjfpOuKBbfMOy!PN@^8kLq%2B&Op>#V9fU8#;q`d@Jnu98PZqUwJV#|1}~_{ z#qy!+t|)8?9GqkLr++5j5+bd;W>3%nqgNyUz}th*Zb9C|ZkWqbh}xMf0a!+%Vn~k@ zWR4|(dEf_ZWksxjGCeHNxd&I(Ae*a{{8xbyAqomv9^5d2{GO5SuZFqnF1mimA|zbf zp?D|*Jf_c?%VwQ*3#)FBG^k$n-?gCCv@2*L-0+Ef`4k`bCBiTCo|7`41NgGgW!m{XWOxw52w-!HX~tKD@oJt!aU&sG>quK5~KMdQUlwZHi4|2GHs z@81GkU`v6JV}|}9mY;rITdHnduw!g^M1SBnRJt&ZBBQ{5oOz!N-uKCL+ZDBatm4h* ztcsG_smHsW($mYmIpLKg8g5*6Bum&W6)y{VlzAS`%JNR~-mx_V4}4RG2BpjEdj7uk zLw>IQt*NQ&$)^~8U9@|C$O+k)=;CG5s%yA5A#4=xV9S&n6r=HE)T##$*k-G!=Do^8ADFkypQQpP~NuCOhIjPx3 zHSq|KpZ_eJD)+X*Df+6@=NDRn?@Y7M*=&nXp5Rj1?au~K;;lV;=_gIuIM3w8rcH&ah zs7bh7lHpO=>c`BIn#li^!0+Mwpu0TwH4(k1o7YlJ$)wd?d-#8#9;GJ8qgIvEHk~YZk6P3p;6U||9#f_ zO#tD|wVlGpyp4B#EKl(|H@azQ?68M8PtsNCry1AtF%(C(XglK};cJeL_HP4l6{T2@ zPcRgA500(+>t#4Wiur#Nj}AFT-FlOd5e= zpT$33666+yF4etJsejK8tLee-y11Q^;#2^8KH{$Gqz%@chf5yHRnD89y&tjDsvj*s z?yLd!v28kB>YyDsJx`zLOp4kqOP;L|XTO$-srNRjq}y#OX(dBx-Qr4Mdu1a1o?zIy z?y`zDFEdWw9ubX#DkirrHJ| z(;K-PwMtGRMH-9F>KjexNu@`xahOu&qTFV)IJ2f6;Iem|Lv+El)BjWFG!zXkX3&9z zVaT(aPs%cngcjVL;0mcflT=QZ@d%gURU5MQbD)ZQ*2TTX1Wdh4y;>MF*HXNNFa*~e zupJYDGbd%7Gd{g$;)2(4T|Ew0MHPl3Y1uswthLd9`&QW4i@aC9DayU%`gH$HRQvXn z+|Yb|Jx*;tizf-@eXy0DWegWjSE|>eh4Csebmm8TL)MzeR4>cv5kyy~kIjVCbL(_H*^;8i_QSA*G%>fGCp-G*gnb*=H zI8rnCtleg9O1e)!%BoBWN!@n8Y=pPnjJ-gv`u%p%dZ*mNYDRhlaUTx5MEu^Hn(rwt zrN0_5h_{xLmE&I7$NdugwM>M^nmk>I&A8x^%pMuI-AB+k85{%kt{lDK8OCVq@{ONq zJl|?f2$qkl366`PFp*<>9kTi))Q{$BG)JNr94nNuhU zU;o?Uk71d$?LQmR)Mh4=I~MAm=Gpxm>BaQGu@%AU|I~qFpb`-G^v~y{c?2o>ThV-K zmvl(0UdzaCTmgv;Rz11fAga8ve8oJ~8}VUWB?)@gpC+@=^7lLHGJ|D!JFbG4CPsud&5^902yc&-g%7`T$&qSH07);HNa^~cY&K#QIzrBk?2=KQ zYheuF7*VNt*N7e*Ipe|^$3uG@2hpO~;~z>|s-G!TtbHEcxf(R{jK^ov)E(M*&9d$4 zqoS4~ymynDS~flg7R4_WtZ6N65#E zf~!(r{7~qv%YMJ1+zZLH}k?r3&p$s3}nn_TFuCmLa_Dl$9OQcClt~q^pO#ahDV{s8U$}HPi zKCf_!6dX$UOTopjr-5Ds)g5ot=z9>TBH5SWBYK`m)CMj(4Weq%7*Q!P73=45o znPo_$<1_V{Kyp6fV%GlyO9PYt5c|CpuK(MMv8&C}hsB@gT!_Dh5RqiTU!SRcMn!on1LXi?ZBtZK^~uWb5QaNXW55sG(4710h|Qpm2F*~(4&MJb<;v%+snG+` z4jSxtn?D-!zmi=GKVPO9WU0!V?^3%ob_coe5M??zs0-SHu9%jD(=TcV{Q@`83R->R z*OIU3{yP=wO^K1#)WnLaJx|us84o*xfo)DqWQW4KBu6P1ctqT(C~@;^tv+8Od}(I` zmvep8l(|j1uKD~$f{*Q3iHO0D(kupQV>6Sv>&BTMA>D1Dp&s=7+Mlat?nsRQUpoaZ%kg0xN&wls#8&~bN zYuDbm^hEh)lu1)Pk=wJn@_VwhvR&Lb^G3;`kl;A>>Aolv`z05L=TO6kYw-?e%W?rZ zoDbTpIU(t8@QiqL)lAp06Tv^n-jg-si4?J)hwNL+3Ct$nEt>TBFm12A?M_~d1RNYd z9+%S|9pEFE6hrA-(-oCje_315R!f(tole5QsT{G8DAt3B622bxxwoEOe4owA9B*a7Wiz?$d3d4$?Ot4hX{FhCn~I1eyMDAd#P=Ph zLC-dy1^Y2TT4PM-Ut>3ljqmBWd(#?MY?oi5Q9C6tq>duzUI=Wd3|njz zkl60MJ~+(D{JF@k_uIg&TL@LbCe6ZQ4ar8=={k)!dCRhn5Mwil)mh@z$egvI_YfH~ zy)>oGHhvAd?S}shVF@w&uUhr+J0~csqeM*BwmBH}S=tPO5tWaMwJ?yGLDh>cLor^w zqfNmCD_|yBWA>`={1iuv&mEw1P=B(DBp1OlNVaOet!;wsFY!KZF&dj5(NOk?Y=`zt1L>%#T+t6jnTEGWMNNN8-MwyoXdn+;;<`7FEz_?hyr_Gqqd%^^N;HZ2 zbUC&BJj3{Oy8P+s;vD+>=X~u)+4NMo2%MWFW6pukK6AI-ns)!~(gj(zt$2Ubf&j6+ z4EL=N>w5I(R;TGZ!Ju{Mg$5*ru7h#rJrI$r276(m7ktw}s9i32^fm#ScnHo!X>cMPGL;9}6L#y5rgJMG#vr z)+J#?alMw`WPh8Y_)VlV51L01!G=claIf&H(yWKmDr>$SU>S@KI5ee54rdWPY& zXcsj`z2Uk!mfW12S0fkc(eKPvymzMrz}A1T`XpzG6x<+eP>|AyiNZY?JGh68nk#Wm z*T;9H>Onn8X0^c#51TsctEhJdcYw7!^V<9^M$SYH-zO2qsc!q50nb0$v!)Zv5(lhA zz5N4VqXSck$PaTnpExUXa6;IK|2t=C&sV!{@Em++3uIhr)kZ1s0FHD%i4EhcL*7!= z+K%7-vmv+JrZr#-`#+5b<3wn{;6)$8Fom%kug-ZdKu8PCd#43qj= zeoqgYQyZ<|p3XBFe*vbws8tpEJ2joV#bTybY|Wd>0Z*TH)rIN{rGw=acB)X8Cw5c? zS`!UiM8w3N&W^Sg270D=k zCe)-%G@kI%!ppthV_#?4p%4P*I86X|tAW=DKEApe16rHWbXlk-N9AXnK{m8n`%=}n zYHxvL)!HnX>=FdNi)MZ`!&)^UT}RTs?k$ed)@HS4Gfmr208Qq}8|^~Z@2?ebqN>>D zxbMp^#%-?LOyOV?livP5*Lx!QB-aq{$Ev~|IbZKO zmG)VUaMdXt?xOFLR%1#}9xNUV|FJz#bDyEL85pQ%T5_Wnm+;PgGS&Ihh^PUaa^H2= z0bt`BIpuT6nY)lhA@g;qYQ}lBv-s!@FLO~iQyTYoWsck>Xh>-2#@|>`W9Y77vmpB{ z!Ofxp6DrYak)vDpyNB^T^PgD7?I(dpnKFqR$bnj#F%^letDZw}>F6|HF-WP|Da!m! z>I)sv>N}(NM8fiaeiq{^6ef@?F4kmoyIb5O0+_@LXhp76&Dp&80H)P_WNvXi(!ZET z?(Ofd^%VIE&X#`WRHM7&R0r4#m1~o)qE!T}5#T2fr*H%0K_WH!5o#$3m7)za-N*);NcO z48(jBXD>qM1;XA*zmS*^$#*66)n-3_+kk)+iF9gRWWj%=*zF$^doAJ{@`&IW0pQ+P z$(gW)6Ek6k~n=Wv>;s^UH&ja@Y# z|B@7q%&78`o%ALI2&GNZOcy8DYpey#%ZaC#*!u2&62P=UL=7M{F|pU5b8-U`F!TDqX(_F|w815pp5gxB z0KcS9BVRmUl_5yxg)jqgGO_mCi`7nQ#dDv;f{)(U-owg5cX(kWYgG%KaV$ z^pdPio@Nr8{A;jx2nz5az+qKaBEf;`e-R-&IXSsdvnNWhLX8{svnsVcAnYO%q>_8} z(Q^to4*``DYVt+Mv-))gP*d?bC7*E|G6~EMb z#P!PDQ445@$u%I(l5gy}IWh4_VHNTmZuc3kA(5dbyQ3*^L_BUk1zWD|$2jNUVlrbx zmsS9N*h~GRviIag+EAQdDlK4miR<{llc7rAoQ{}cA+-&i1)pphe^O%CsJVl);-=w5 z3Wt-kjoJLTO$B>=`irU8AtEzr{JsTI zIsaf>hwwnZlCwHK<*uypYBz#*%z>afH^kxOkz2jmg@(qG(Y`l6QKz#ukeiKr06~44 zSPMcZqXs^j=N(P{5muCUW|I!gPwdBD||EBN*gSy24R?J!rRjx1xy&#m0?5Tw;Vss=r zDFP$>g<}OylWZ|~3$6&(Z3U>Rn%x@D%$6KR?XlA_1jzRfN+zyW?ZwM4@4HpRQ zs)0N2@$@{{lc;AEYfO=?blo!iSl0UI#mKnAPx00|1GdGqFG;K2Z?O^uljJw>m_IHp zi0lmyxNSZnNC1zYRFJc( zUY3)TCjW1hwB##nE4GZC8$TS+rs;-=BNJ?alYgwk~cdy5~IA~ zvjXxT(YFEKZ4BzN^i>T9Uj)7=L_`T_POd>rD*o3UUYbj}fe?p6hx**G{Kg-f+WL22 z#KF-yMp#u>blD z3A}#7oH^ede1?J)i*w`tUW{_INls71++nXEDK0&Ibn4jyE4W8$A%&fX2>rP62)$62 z7h|mnSBnIjh;Kg8{6!)CLHU7FTZ(nB@Pbk&^)iCO5M$Ecjhx2&yMx{EQY_F8`O~Ew z4H*k999oU}n*y;}?{Vnwgbf(!=&J2Y<2qDp-qg&b+vJY-dA1XrBX=_>+;>jcg^7iSx&G7DzWJ}0NEh;^q|JuZ9_ z1Pjg0&1~B9l$2G$lXWF@HkHydPQB^r{KN<`5__P%A$IewkUoq6;&+~3D^>t;jJct} z_S1XJhk-*JllmSh=(DpN*31lUHFJp6S-O*h`)L_v??9Ze;U-)~m@j)j;Bnm(t*xq6yd9k}+vLlcc@q_?}%0$)dXEc@1Lvk;l`9w{Ws zZPMSln;jF`%C;diFwi2U^=`kc^>KV@dU`tMS8{;KXA>1Fh~V>Ue01O~C4mOKsWkOi zfC>kcc>%C&2#YPnfjx-qxmDph|ROL%|J!XE$GfGe_b$ALaQ9%132MknJm~)a1MRi`*m*I|s6) zZ1+Q>zV$Vv8w_P4tyHqsHz!R4XwCW2TfYsFhU2?ddi3}dv!^R)c+L-zvbXl$7%$MHgJYW z$7-yCJ$(0o%&h>s%>SiM^n;8#!s&-hl# zn$k$hIBZVb?p`woK8ai1cKKQlS-Gq7TtCnlKfC*3TJ;$ZO&J|aU9_1{15H8e>kOL# zW+LH`jL5j1W66n~qy0;J!vM#c-yiK9cg_rJOdo z-%kCs^x&%!ZxZLfN}HanB1o6CwviUkrd}Xie z!l9RXaSyUR(?Fsm$Qkn7tAbPNG(oahh3SyHNj^tEIaRz^hlvrP%8W-A5wPaqa5c7_ z^1L$OYqZ+MmSpv>$X$CcOic%rOWR6K!8Z&ud2L)a-#G4Sy@}=Vr%zloS6H@AH6Sp2m!O< zzn&GRt)|N|A90mvH9R&iD5Y=tj=6q1{)&W($Sv`B(=6inoNmkBj49Z@i8639d^IDO zAH;Zp5wa*kR76}-9v@j*cX1QD;r1*5f=e95mwU?vj7iE(>J^IdD=v#SXO`7f3*Xg# zHp)_cjFWAJzeSiT?54}WE^_IKWhX0lHw=DDPQG9`6x3l()TF$I4^Rg4s522&7$ihO z`2jww8lnsYe?LUmg55+oU?H^lZaqmr5=Zq?S+6%36e^kbuQQDJw=I4K{+_QmHG}|l zigpc~nYUoJ`gckZ%U2#rOb2tq8o-z^B96(xbs-#+j{C`J{5EoS;27(~Wh8%r^vO51 z%*}VdI3&;J+#ZC{UseiXOR~iNe@R0iic2~P|4g8RthK2@5=7rzu;}_Co z3bGvJAqeQh9f2Q?0{CXRBR8YuFJYB$(OrM|1VBaiSt7;4oMc zz7E^BH{kA!f|3$JJauqJjVY|k~2GK04~`!=6nEb;g`44H8v8v)(iq6`iRwF^6Se6wo#Rl%SfnUTE;pm z5E-%Y!{PWN5m7ZYHSOWi5a&MTl&^E$dfzX*so&bx#ZIKz<=FZf;e8-gkiEOTsc>0& zw$tE$bBP9#x>zM~q!#pjRrhbYD&Oj=(Q_{j-1%fzCV4t#QQ^5~;=VIOb|0Tc#>Isf zl2cfy>=WzV)X+c`78Yh;_z^R~yW5##!hURC>Oo>yI4)__AqJB8=_KW~_mj^70n)PAvJqgHx^JtOz zumiOI5wX);J(0|;%N01CbF|E~HPnwP0*VADx#R4dp6<+&EVxaU8h>DV=ySHK03~f- z`0fM77yq$DSh>$!7M4{yEr!F%k`_Q*XjlPVrfLjj$Qnw`0d7_oVaY<+;7jWjXmcvA$l#o zqQ6TFQ_AV8=#~BEz=cKUEAb2iu1y{Vvv21c11A%~D=0fV2E_f}7$!3_^9BfqIMKh9kb?%&lHSU>QrbT9kIJls z{P-9IVitew$f277uXYP4W|_D~ufUCN(bdv;c=l8RgqR;@*Wb%`7#y>4y18esa@2tI z5DBHyVYA*SLYB7wOyehcJaA$JCnF<+5QlsQr>csQuWqmpvaz!tM4Mit%QU+ZL4+Kp zavbyV#dY+0yMhIrqi7ivLLT@e})hngLUSr0baXzJ(c5o=MPH0O^g(QoL+%_vn zWzfJ-_-;87sK$c@v&r@o3iPVC#r;qmEU%zZot$!#9JHC8CF!#~z}>3qMRzj??}q;X zvG)aBIBV9@4K6LBe-vwdoK~!dX=zeMoH^(tN_9xJ-lJM;F0%HRyY?w9E=g1{H^sUr zg#!`YI;s|GQLfLvhuYfOkifj>Dd>?A z(RVj{0X6G`;pnVLqhHdc1f;QO>5b^sD#is}djAS^*lVk+!Mj}OE}TEs>1p3ZaH;W! zf0}Mi`M9G>?o=t40QGCY_iuo^*){AwK{!M?XH}u5q<0a#MH?lQ4Zf^juBWYSB_^Dk z*|0TdAoHcDNCk)dL(S`2}wLD!1$-#--$eK=y~k_o{KoVvjh{|H|f13tc)FfpFa^A{z{r)&Inx{Avs= z!-bB`_jbeEQ!bdcE(hj@z9uIL55SsU9{R?T-l2535Z}fJq-sR!h z)!7~a1j@lNPOhnOmPdd$!7$MMdUU(?phA!16VIF|DK-Ns_M7N7CJUj}83$@4!+dwo ze37lY4_cNg<*cO#hk`wSjj@BKKb6onBd4X=hzzN!zt}MKqu&VKH~OWYWt9t1RSEX2 zSnFr76q7~>j1^f4zL!-i(DKZU8E1X`wZ_Ro4_)1C_x8IUx&R5tYtV&5mgTcOcV@zz z=9fFHPIu>V=uNty1AOr4XqV%S(a=-a7r?v_K@RqLY4D$rN54sq_h2V1(Hmq>eTu{$ z)tX&RuYl{);YS}DvmD~&7Zt-EUv79_m^@Tm-amRj1aj!Q`x;Kg`GrK%|p{bIWVzUM{xyk?g*mseXuwiTNO+h$n#%f^RK-rlHNhJ#G*7$7wa|)tmdizff8GB&C7HSg9Su(JOb||t^RPZ3FG{KUVxwp zxcN#jX9H37QAT7i@IPXGdzl>vAP|cL`FIy}%=kyw8^6orwojaf)%5CjStv{ZE=G|n zFUS_JsHo6rD$x;s_GL75*7|q?Zmpf#C*?`licv_}p<_X2FNQNmsPWfpN!F4R+V=Lt z-Dn^xT)B~CA--888v8t2KR+O#^_xXV9=E@$s-K1M07ys`duR9Ts;IPd$cxgg^8Myq zMhDl#=HTX0G&yJg<#+G1-I95obuBH7ZZH|Bf|i>C>MD(d7a@e0+(BcOBnmb%K5p44 zSM9PnK-Wt28A zNDZ>ddjAYZX*@ZHpZ3(q*tld~&2v}2sUzoCLNU6=9oVX*aPqw;mU>;Oynv6Z$Xo&o zAdr!`7x`+L02LKD8tUmq{{3rBN>0xBD7My69d`2uw>`#9(SSERMlIB)8!kj&){g089ogE;k{kOjON(_tMONae^R%0%ewGJcYz$N4V;3&fP{?HN}{!Q_bJUuI z59RYFYQd3#nRYD-tR1cHe=B~Ht?;;vwv;8MFLKo$ks&D~gSoSZ-SC6R>5ycZ3B&86 zM3^}8UAV@6ClmVL{l~s4u+aJzZm2Dpw;wIpvmLPdSZ9yTRpOqPXXc8u1 zEvr+?zCLcJaB~g6G#j-m$h+mmGR#$1LYj;ZRQC@#P`<0Z=1D>HQ+hpm%dgJVAEW=F zARs1kjMZR&Ab`g<9xSLz)o__3304HXML{YC03r*`?`tV+mAj)xy4A>x{QM*#uYacU z?wBCoM&IVo{?xJ52_UDSSlM6dn6UtdDT#O=+qQ32I_6Kh(ZWqiY{~oi)Q>4f!N_P= zvSFPPY4DUAJQe+4zTa5_VS5pnYaUl{^t9*|9?2k!ggf6<1%FD8KQ$}G8(zCNZ)Cxr z_U5QWrrhdkEkiT|M@n7u9%rBO)QY?6ij*6Sjq!S(M- zK}s#ZS0lykDZDv&z?_PCP5HHH&Y5&A&Kn~P z?z?kTig7f`UPDuANR~1>jaEgj0^o=;X!_|RqkRP z6}kwSXfSY5UZ~#zi(Xz0&v@wX`x@FpEiJ8_mX-xq!*^M7H$IK}c?Fx(Rjjpd7fVa7 zi=pt^BDeor=rw(Mc?EQQC3`r258en9Rv8G2(NRYHF!Xa0*6C(BWH<4>M-3X?_oJX( zRdq0otlme>{35T`@ziSH$6qrhNv~BhHC>k4!ythVNm%rp*p(A&Gbs?G1+|adBk*bI zm5JkML=$;B^-U{mZA7Z3ePh|G*q$LV9S@n6_^CG?w9!YP5MffuchM*bN@#IU*fpwY1>}*O7qlfj z8XwG-mPVd=s0cg?LqH>+eF4?Qfciu}Q$F{Dkbpt5gGRCzL+->}3PO9efy(t!eEdP} z^eI?x0CX%52%WFJ-vzKT@c|_ZF_FGS!A63p+h5xWxX#b;aqBAEXzFowr6jO@rp#2@ z_jKAOvdi2cwV<}9py0va;GjAwbFQ6+G{IMWLBv5Vo4#OHBXNxe7m{M$-?U1>d3?4o zJo00`o>ejxH!^uj5!TRF1VaeP(xR7OML|$M$lRtrD)099XN6!s!o^AY=H(ZyVR1(g zYgx@NS;l2v-sOWIij9q(Ina<-@XIL(_@1SmY%3;@n7FBLBj_kT(T=|0Yh_wv4ac<% zZ!0?=`}ZVky`c>(4Q3r?Vxqi=T*Uovs%ZdJYdiFz!xS`7SS^N%zuVm>e>ziFLyI-r zmk;t9^oTPSV8!#&CL&A8OH6-u#Z0T4thn$QjxbLXzRo{?nlUihz;Y88q~uC-sYD7A zt6RK$PS-lvs$!C71^K}P*aHk)GUIPp@W2}tg)c_dMJT3Wv6PR{5!&VzG;yU$bWI~oo^)A? z!4_cWB#aJyFibZxat=%^^S^Ka!8v}MAFPBG|2;HRB8`1UgdH{lI)c!ij-_&;ZK_D_ znZ)A6Axfqqv)oMhGo&cl&dw}Tvf<~6nl|o*D z;we11P%|IUnfj@GR@i_jo_G3uakS1l-vbbOh1Y?(mbUhrtMR?Xr~ihipq2ltp0z$d z9lEUbKWTFPHrM`cTPqVifjx4$K0Yg3xLI{sEHmr-$^T;aLxb-_*tJBbs40qZ@Ru4s zq6Mk#Ws;o&SF;>!l@}S z;EvjY{jT>Clwh-5+S321C;~^Noz6rs8@#!v*AKVOB7@&o4DuvE&%Ltl;{XaECE88_ z;1pOxhx(`$5Ve1^k)0g34TL@h7dX^MT5=UzC+ zz{YqXNqTxZA%H`3bGQl`02F=Y97mWw6r-wI`lU0xwU?hBF}fFnGjq=>mk#?IJ%Jyt z`98J4_LH~wE+klW*k935n1I8wG2|6e3SgeD$$ubebSUI{vbQ~Iv!-Mw)M{ULw|IAi*xEk}I^sjP!ry*+API$Z>(=+S!38E&^Q5iA9MT zta8{xoo^{-FZ4=Q>!cX_bwDBLv{M*u;Jue_#z>TqO3Bt}322E_ zQ8(+-&r6i8_>()oOQ>rdXTt&2krr;+7tU;m_e8k#ha)s}7#c{8H9GrvK>0630r`P<((&7$ zrIDUf7{340IKQOFS?iYJ@;M=Sp!`92RGAnLL0if-I$T(w!Yc5yx^kd6n9I;(-I_F$ zW8edm^3|KV#$l14!eATlztf7v5TP3$m#W+~|2yCDtOr34kjVfLrmQzS2pHCIE!M%s z`tNnAK~3YKCTH&-8Ku83Lo4R~WAuw6gEFyPE}^CVGcz-@G3QYZrsrf>->&Lyk8rJt zJ<Mxs!;+|bQVt)L>>ZUvR#-XTxMjh?_}2J;%? z1j9qY^OIlTY)HRVRvL6pmYa6=J^za6bwVNy8D1^->Fwz%w9b&OzK^U;kDK*&#I>QT zuzHq8RBt2Yt7lk{XVDV}`6+E$nH)11_wn}peFY?Xn(&=)UOMZTgNb_83SnotShgrg zA9l=$KP&Imoc<8nR_F~T_c~`qLP02Cx3f98BUDBmT6Nr5t&xDCYx-{9g{^q{@2jl< zTpbE{?3nKEXQZUn(wN8W@>@u%!C>7J-jxaguFjQwp23pS%N>yq!jydV(b_u80}&{= z>SR%4zUzV-_G>UOPd4{$nxX?Y8nmCLs`Xmfhyxg~K*6cEJ(h<9`ugbLVDwNqhJhk^ zWY5oVF>3b1nCR9G({%yi)2+_i`bPrHEBU$cu%tBl%=HVx>q}ZBnOg`>8KCXu6$n(* z_!J@;I@7S!H|^Qj*wjr;+ewx?+;H}NK$Q@W5^jq-SFL_Y5;ZQY_qoLIQ(e81jZD=d;)^Cg9fG0y z`=j~&k-D+*j_rPu1D6832L_!5WrOd9Yf?(eEIxq(E;(8bKs%KjtP<8n2m0T$i?KEC z3|3ZjI=*EtpWgm*jLve&QYM;FTEKaQn)+-1icEs_hQ%vTr7pvCQKbUL1_JampB3E0 zFf+TXvGLKnckfa~T+G{73N4A{(zVC+cV?Y7ENK1~KN7S{sx3=q*R?x~EhA!h4P@vx z6o*uTg_mRep@5J2(gF9R8UF%?w-wXTbrK&nWzruv-6e#I;`nvZs8IQw`K48(DBSfZ zRD%z2g<2-|4>2Asj4lVNh&eIdGATKga_gRVNt5CDsL8uVX4#UKvPr-pQY2Z_O$GN}gDn zfUX&q^jL?@`|G!F&o*9n*>TBMT|KiawB;fSXVL{=xYMq;;(MSeYix5%Mrh>mJvF%oq)*Ea}9kO`VoqKo*S4OUnS$W`4!eCSim0C4wL7{>rGX2bwq=pcOOU?R~P{-iJe7%~{ zGD{MRKp1zEeRWe#WU8*NPQ|zQJsewbTR}Y}I+3E&vGxn^L1xAZ?}WRL}qbBy;ti zXwV5`=Sn_ck;AuoQ@X0lq&V0#A)JWy$|TiKC}Boz_fMBlg7gM5)T`yyh=4$G*H`